diff --git a/README.md b/README.md index 456ab343..b11e9cf1 100644 --- a/README.md +++ b/README.md @@ -11,12 +11,12 @@ Currently supported tasks include: * Driving in traffic * Navigation -Each task comes with its own custom evaluation metrics that can help compare autonomous driving solutions. -The main component of the ego vehicle is the brain, which receives sensor data, manipulates it, and generates robot control commands based on it. -The inner part of the brain can be controlled by an end-to-end model, written in Tensorflow or PyTorch, a reinforcement learning policy, or even an explicitly programmed policy. +Each task comes with its custom evaluation metrics that can help compare autonomous driving solutions. +The main component of the ego vehicle is the controller (brain), which receives sensor data, manipulates it and generates robot control commands based on it. +The inner part of the brain can be controlled by an end-to-end deep learning model, written in Tensorflow or PyTorch, a reinforcement learning policy, or even an explicitly programmed policy. The software provides two main pipelines, a graphical user interface (GUI) and a headless mode (scripted). -The first one is intended for testing one brain+model at a time and debugging it visually while the headless mode is intended for running lots of experiments at the same time for comparison of a batch of brain+models in different scenarios. +The first one is intended for testing one brain+model (controller) at a time and debugging it visually while the headless mode is intended for running lots of experiments at the same time for comparison of a batch of brain+models (controllers) in different scenarios. ![alt text](./assets/behavior_metrics_paper_behavior_metrics_full_architecture.png) @@ -68,13 +68,25 @@ Behavior Metrics provides two different evaluation modes, GUI evaluation and hea In this mode, activated with flag `-g`, the simulator and software application are displayed. -![alt text](./assets/behavior_metrics_paper_behavior_metrics_gui.png) +* Video: + +[![GUI video](https://img.youtube.com/vi/ze_LDkmCymk/0.jpg)](https://www.youtube.com/watch?v=ze_LDkmCymk) + +* Scheme: + +![GUI scheme](./assets/behavior_metrics_paper_behavior_metrics_gui.png) #### Headless In this mode, activated with flag `-s`, the evaluation is conducted without graphical interface. -![alt text](./assets/behavior_metrics_paper_headless.png) +* Video: + +[![Headless video](https://img.youtube.com/vi/rcrOF5t3MC4/0.jpg)](https://www.youtube.com/watch?v=rcrOF5t3MC4) + +* Scheme: + +![Headless scheme](./assets/behavior_metrics_paper_headless.png) ### Robot controller diff --git a/assets/behavior_metrics_paper_behavior_metrics_full_architecture.png b/assets/behavior_metrics_paper_behavior_metrics_full_architecture.png index 450ec1eb..951b4aed 100644 Binary files a/assets/behavior_metrics_paper_behavior_metrics_full_architecture.png and b/assets/behavior_metrics_paper_behavior_metrics_full_architecture.png differ diff --git a/assets/behavior_metrics_paper_behavior_metrics_gui.png b/assets/behavior_metrics_paper_behavior_metrics_gui.png index 858598c4..b520e85a 100644 Binary files a/assets/behavior_metrics_paper_behavior_metrics_gui.png and b/assets/behavior_metrics_paper_behavior_metrics_gui.png differ diff --git a/assets/behavior_metrics_paper_headless.png b/assets/behavior_metrics_paper_headless.png index 65e65011..71ec6838 100644 Binary files a/assets/behavior_metrics_paper_headless.png and b/assets/behavior_metrics_paper_headless.png differ diff --git a/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_50_km_h.py b/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_50_km_h.py new file mode 100644 index 00000000..b698bd8e --- /dev/null +++ b/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_50_km_h.py @@ -0,0 +1,191 @@ +#!/usr/bin/python +# -*- coding: utf-8 -*- +import csv +import cv2 +import math +import numpy as np +import threading +import time +import carla +from os import path +from albumentations import ( + Compose, Normalize, RandomRain, RandomBrightness, RandomShadow, RandomSnow, RandomFog, RandomSunFlare +) +from utils.constants import PRETRAINED_MODELS_DIR, ROOT_PATH +from utils.logger import logger +from traceback import print_exc + +PRETRAINED_MODELS = ROOT_PATH + '/' + PRETRAINED_MODELS_DIR + 'CARLA/' + +from tensorflow.python.framework.errors_impl import NotFoundError +from tensorflow.python.framework.errors_impl import UnimplementedError +import tensorflow as tf + + +#import os +#os.environ['CUDA_VISIBLE_DEVICES'] = '-1' + +gpus = tf.config.experimental.list_physical_devices('GPU') +for gpu in gpus: + tf.config.experimental.set_memory_growth(gpu, True) + +class Brain: + + def __init__(self, sensors, actuators, handler, model, config=None): + self.camera_0 = sensors.get_camera('camera_0') + self.camera_1 = sensors.get_camera('camera_1') + self.camera_2 = sensors.get_camera('camera_2') + self.camera_3 = sensors.get_camera('camera_3') + + self.cameras_first_images = [] + + self.pose = sensors.get_pose3d('pose3d_0') + + self.bird_eye_view = sensors.get_bird_eye_view('bird_eye_view_0') + + self.motors = actuators.get_motor('motors_0') + self.handler = handler + self.config = config + self.inference_times = [] + self.gpu_inference = True if tf.test.gpu_device_name() else False + + self.threshold_image = np.zeros((640, 360, 3), np.uint8) + self.color_image = np.zeros((640, 360, 3), np.uint8) + + client = carla.Client('localhost', 2000) + client.set_timeout(10.0) # seconds + world = client.get_world() + + time.sleep(5) + self.vehicle = world.get_actors().filter('vehicle.*')[0] + + if model: + if not path.exists(PRETRAINED_MODELS + model): + logger.info("File " + model + " cannot be found in " + PRETRAINED_MODELS) + logger.info("** Load TF model **") + self.net = tf.keras.models.load_model(PRETRAINED_MODELS + model, compile=False) + logger.info("** Loaded TF model **") + else: + logger.info("** Brain not loaded **") + logger.info("- Models path: " + PRETRAINED_MODELS) + logger.info("- Model: " + str(model)) + + self.previous_bird_eye_view_image = 0 + self.bird_eye_view_images = 0 + self.bird_eye_view_unique_images = 0 + + self.first_acceleration = True + + + def update_frame(self, frame_id, data): + """Update the information to be shown in one of the GUI's frames. + + Arguments: + frame_id {str} -- Id of the frame that will represent the data + data {*} -- Data to be shown in the frame. Depending on the type of frame (rgbimage, laser, pose3d, etc) + """ + if data.shape[0] != data.shape[1]: + if data.shape[0] > data.shape[1]: + difference = data.shape[0] - data.shape[1] + extra_left, extra_right = int(difference/2), int(difference/2) + extra_top, extra_bottom = 0, 0 + else: + difference = data.shape[1] - data.shape[0] + extra_left, extra_right = 0, 0 + extra_top, extra_bottom = int(difference/2), int(difference/2) + + + data = np.pad(data, ((extra_top, extra_bottom), (extra_left, extra_right), (0, 0)), mode='constant', constant_values=0) + + self.handler.update_frame(frame_id, data) + + def update_pose(self, pose_data): + self.handler.update_pose3d(pose_data) + + def execute(self): + image = self.camera_0.getImage().data + image_1 = self.camera_1.getImage().data + image_2 = self.camera_2.getImage().data + image_3 = self.camera_3.getImage().data + + bird_eye_view_1 = self.bird_eye_view.getImage(self.vehicle) + bird_eye_view_1 = cv2.cvtColor(bird_eye_view_1, cv2.COLOR_BGR2RGB) + + if self.cameras_first_images == []: + self.cameras_first_images.append(image) + self.cameras_first_images.append(image_1) + self.cameras_first_images.append(image_2) + self.cameras_first_images.append(image_3) + self.cameras_first_images.append(bird_eye_view_1) + + self.cameras_last_images = [ + image, + image_1, + image_2, + image_3, + bird_eye_view_1 + ] + + self.update_frame('frame_1', image_1) + self.update_frame('frame_2', image_2) + self.update_frame('frame_3', image_3) + + self.update_frame('frame_0', bird_eye_view_1) + + self.update_pose(self.pose.getPose3d()) + + image_shape=(66, 200) + img_base = cv2.resize(bird_eye_view_1, image_shape) + + AUGMENTATIONS_TEST = Compose([ + Normalize() + ]) + image = AUGMENTATIONS_TEST(image=img_base) + img = image["image"] + + self.bird_eye_view_images += 1 + if (self.previous_bird_eye_view_image==img).all() == False: + self.bird_eye_view_unique_images += 1 + self.previous_bird_eye_view_image = img + + img = np.expand_dims(img, axis=0) + start_time = time.time() + try: + prediction = self.net.predict(img, verbose=0) + self.inference_times.append(time.time() - start_time) + throttle = prediction[0][0] + steer = prediction[0][1] * (1 - (-1)) + (-1) + break_command = prediction[0][2] + + speed = self.vehicle.get_velocity() + vehicle_speed = 3.6 * math.sqrt(speed.x**2 + speed.y**2 + speed.z**2) + + if vehicle_speed < 50 and self.first_acceleration: + self.motors.sendThrottle(1.0) + self.motors.sendSteer(0.0) + self.motors.sendBrake(0) + else: + self.first_acceleration = False + self.motors.sendThrottle(throttle) + self.motors.sendSteer(steer) + self.motors.sendBrake(break_command) + except NotFoundError as ex: + logger.info('Error inside brain: NotFoundError!') + logger.warning(type(ex).__name__) + print_exc() + raise Exception(ex) + except UnimplementedError as ex: + logger.info('Error inside brain: UnimplementedError!') + logger.warning(type(ex).__name__) + print_exc() + raise Exception(ex) + except Exception as ex: + logger.info('Error inside brain: Exception!') + logger.warning(type(ex).__name__) + print_exc() + raise Exception(ex) + + + + + diff --git a/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_70_km_h.py b/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_70_km_h.py index 80e75693..1e8d8b65 100644 --- a/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_70_km_h.py +++ b/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_70_km_h.py @@ -134,7 +134,7 @@ def execute(self): self.update_pose(self.pose.getPose3d()) - image_shape=(50, 150) + image_shape=(66, 200) img_base = cv2.resize(bird_eye_view_1, image_shape) AUGMENTATIONS_TEST = Compose([ diff --git a/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_V_MAX_30.py b/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_V_MAX_30.py index bda34764..4e7bea2b 100644 --- a/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_V_MAX_30.py +++ b/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_V_MAX_30.py @@ -131,11 +131,10 @@ def execute(self): self.update_pose(self.pose.getPose3d()) - image_shape=(50, 150) + image_shape=(66, 200) img_base = cv2.resize(bird_eye_view_1, image_shape) AUGMENTATIONS_TEST = Compose([ - #ChannelDropout(p=1.0), Normalize() ]) image = AUGMENTATIONS_TEST(image=img_base) diff --git a/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_broken_input.py b/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_broken_input.py index 37fcd41e..0448a2d1 100644 --- a/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_broken_input.py +++ b/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_broken_input.py @@ -125,7 +125,7 @@ def execute(self): ] AUGMENTATIONS_TEST = Compose([ - GridDropout(p=1.0, ratio=0.9) + GridDropout(p=1.0) ]) bird_eye_view_1 = AUGMENTATIONS_TEST(image=bird_eye_view_1) @@ -139,7 +139,7 @@ def execute(self): self.update_pose(self.pose.getPose3d()) - image_shape=(50, 150) + image_shape=(66, 200) img_base = cv2.resize(bird_eye_view_1, image_shape) AUGMENTATIONS_TEST = Compose([ diff --git a/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_broken_input_2.py b/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_broken_input_2.py index 37fcd41e..a9eab9b0 100644 --- a/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_broken_input_2.py +++ b/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_broken_input_2.py @@ -139,7 +139,7 @@ def execute(self): self.update_pose(self.pose.getPose3d()) - image_shape=(50, 150) + image_shape=(66, 200) img_base = cv2.resize(bird_eye_view_1, image_shape) AUGMENTATIONS_TEST = Compose([ diff --git a/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_previous_v.py b/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_previous_v.py index 9ab3105a..1db1f353 100644 --- a/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_previous_v.py +++ b/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_previous_v.py @@ -133,7 +133,7 @@ def execute(self): self.update_pose(self.pose.getPose3d()) - image_shape=(50, 150) + image_shape=(66, 200) img_base = cv2.resize(bird_eye_view_1, image_shape) AUGMENTATIONS_TEST = Compose([ @@ -147,7 +147,7 @@ def execute(self): self.bird_eye_view_unique_images += 1 self.previous_bird_eye_view_image = img - velocity_dim = np.full((150, 50), self.previous_speed/30) + velocity_dim = np.full((200, 66), self.previous_speed/30) new_img_vel = np.dstack((img, velocity_dim)) img = new_img_vel diff --git a/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_previous_v_50_km_h.py b/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_previous_v_50_km_h.py new file mode 100644 index 00000000..c788baf9 --- /dev/null +++ b/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_previous_v_50_km_h.py @@ -0,0 +1,197 @@ +#!/usr/bin/python +# -*- coding: utf-8 -*- +import csv +import cv2 +import math +import numpy as np +import threading +import time +import carla +from os import path +from albumentations import ( + Compose, Normalize, RandomRain, RandomBrightness, RandomShadow, RandomSnow, RandomFog, RandomSunFlare +) +from utils.constants import PRETRAINED_MODELS_DIR, ROOT_PATH +from utils.logger import logger +from traceback import print_exc + +PRETRAINED_MODELS = ROOT_PATH + '/' + PRETRAINED_MODELS_DIR + 'CARLA/' + +from tensorflow.python.framework.errors_impl import NotFoundError +from tensorflow.python.framework.errors_impl import UnimplementedError +import tensorflow as tf + +import os +os.environ['CUDA_VISIBLE_DEVICES'] = '-1' + +#gpus = tf.config.experimental.list_physical_devices('GPU') +#for gpu in gpus: +# tf.config.experimental.set_memory_growth(gpu, True) + + +class Brain: + + def __init__(self, sensors, actuators, handler, model, config=None): + self.camera_0 = sensors.get_camera('camera_0') + self.camera_1 = sensors.get_camera('camera_1') + self.camera_2 = sensors.get_camera('camera_2') + self.camera_3 = sensors.get_camera('camera_3') + + self.cameras_first_images = [] + + self.pose = sensors.get_pose3d('pose3d_0') + + self.bird_eye_view = sensors.get_bird_eye_view('bird_eye_view_0') + + self.motors = actuators.get_motor('motors_0') + self.handler = handler + self.config = config + self.inference_times = [] + self.gpu_inference = True if tf.test.gpu_device_name() else False + + self.threshold_image = np.zeros((640, 360, 3), np.uint8) + self.color_image = np.zeros((640, 360, 3), np.uint8) + + client = carla.Client('localhost', 2000) + client.set_timeout(10.0) # seconds + world = client.get_world() + + time.sleep(5) + self.vehicle = world.get_actors().filter('vehicle.*')[0] + + if model: + if not path.exists(PRETRAINED_MODELS + model): + logger.info("File " + model + " cannot be found in " + PRETRAINED_MODELS) + logger.info("** Load TF model **") + self.net = tf.keras.models.load_model(PRETRAINED_MODELS + model) + logger.info("** Loaded TF model **") + else: + logger.info("** Brain not loaded **") + logger.info("- Models path: " + PRETRAINED_MODELS) + logger.info("- Model: " + str(model)) + + self.previous_speed = 0 + self.previous_bird_eye_view_image = 0 + self.bird_eye_view_images = 0 + self.bird_eye_view_unique_images = 0 + + self.first_acceleration = True + + + def update_frame(self, frame_id, data): + """Update the information to be shown in one of the GUI's frames. + + Arguments: + frame_id {str} -- Id of the frame that will represent the data + data {*} -- Data to be shown in the frame. Depending on the type of frame (rgbimage, laser, pose3d, etc) + """ + if data.shape[0] != data.shape[1]: + if data.shape[0] > data.shape[1]: + difference = data.shape[0] - data.shape[1] + extra_left, extra_right = int(difference/2), int(difference/2) + extra_top, extra_bottom = 0, 0 + else: + difference = data.shape[1] - data.shape[0] + extra_left, extra_right = 0, 0 + extra_top, extra_bottom = int(difference/2), int(difference/2) + + + data = np.pad(data, ((extra_top, extra_bottom), (extra_left, extra_right), (0, 0)), mode='constant', constant_values=0) + + self.handler.update_frame(frame_id, data) + + def update_pose(self, pose_data): + self.handler.update_pose3d(pose_data) + + def execute(self): + image = self.camera_0.getImage().data + image_1 = self.camera_1.getImage().data + image_2 = self.camera_2.getImage().data + image_3 = self.camera_3.getImage().data + + bird_eye_view_1 = self.bird_eye_view.getImage(self.vehicle) + bird_eye_view_1 = cv2.cvtColor(bird_eye_view_1, cv2.COLOR_BGR2RGB) + + if self.cameras_first_images == []: + self.cameras_first_images.append(image) + self.cameras_first_images.append(image_1) + self.cameras_first_images.append(image_2) + self.cameras_first_images.append(image_3) + self.cameras_first_images.append(bird_eye_view_1) + + self.cameras_last_images = [ + image, + image_1, + image_2, + image_3, + bird_eye_view_1 + ] + + self.update_frame('frame_1', image_1) + self.update_frame('frame_2', image_2) + self.update_frame('frame_3', image_3) + + self.update_frame('frame_0', bird_eye_view_1) + + self.update_pose(self.pose.getPose3d()) + + image_shape=(66, 200) + img_base = cv2.resize(bird_eye_view_1, image_shape) + + AUGMENTATIONS_TEST = Compose([ + Normalize() + ]) + image = AUGMENTATIONS_TEST(image=img_base) + img = image["image"] + + self.bird_eye_view_images += 1 + if (self.previous_bird_eye_view_image==img).all() == False: + self.bird_eye_view_unique_images += 1 + self.previous_bird_eye_view_image = img + + velocity_dim = np.full((200, 66), self.previous_speed/30) + new_img_vel = np.dstack((img, velocity_dim)) + img = new_img_vel + + img = np.expand_dims(img, axis=0) + start_time = time.time() + try: + prediction = self.net.predict(img, verbose=0) + self.inference_times.append(time.time() - start_time) + throttle = prediction[0][0] + steer = prediction[0][1] * (1 - (-1)) + (-1) + break_command = prediction[0][2] + speed = self.vehicle.get_velocity() + vehicle_speed = 3.6 * math.sqrt(speed.x**2 + speed.y**2 + speed.z**2) + self.previous_speed = vehicle_speed + + if vehicle_speed < 50 and self.first_acceleration: + self.motors.sendThrottle(1.0) + self.motors.sendSteer(0.0) + self.motors.sendBrake(0) + else: + self.first_acceleration = False + self.motors.sendThrottle(throttle) + self.motors.sendSteer(steer) + self.motors.sendBrake(break_command) + + except NotFoundError as ex: + logger.info('Error inside brain: NotFoundError!') + logger.warning(type(ex).__name__) + print_exc() + raise Exception(ex) + except UnimplementedError as ex: + logger.info('Error inside brain: UnimplementedError!') + logger.warning(type(ex).__name__) + print_exc() + raise Exception(ex) + except Exception as ex: + logger.info('Error inside brain: Exception!') + logger.warning(type(ex).__name__) + print_exc() + raise Exception(ex) + + + + + diff --git a/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_previous_v_70_km_h.py b/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_previous_v_70_km_h.py index 62952e24..70100b04 100644 --- a/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_previous_v_70_km_h.py +++ b/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_previous_v_70_km_h.py @@ -135,7 +135,7 @@ def execute(self): self.update_pose(self.pose.getPose3d()) - image_shape=(50, 150) + image_shape=(66, 200) img_base = cv2.resize(bird_eye_view_1, image_shape) AUGMENTATIONS_TEST = Compose([ @@ -149,7 +149,7 @@ def execute(self): self.bird_eye_view_unique_images += 1 self.previous_bird_eye_view_image = img - velocity_dim = np.full((150, 50), self.previous_speed/30) + velocity_dim = np.full((200, 66), self.previous_speed/30) new_img_vel = np.dstack((img, velocity_dim)) img = new_img_vel diff --git a/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_previous_v_broken_input.py b/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_previous_v_broken_input.py index 2ac2ae31..c5bf0edc 100644 --- a/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_previous_v_broken_input.py +++ b/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_previous_v_broken_input.py @@ -126,7 +126,7 @@ def execute(self): ] AUGMENTATIONS_TEST = Compose([ - GridDropout(p=1.0, ratio=0.9) + GridDropout(p=1.0) ]) bird_eye_view_1 = AUGMENTATIONS_TEST(image=bird_eye_view_1) @@ -140,7 +140,7 @@ def execute(self): self.update_pose(self.pose.getPose3d()) - image_shape=(50, 150) + image_shape=(66, 200) img_base = cv2.resize(bird_eye_view_1, image_shape) AUGMENTATIONS_TEST = Compose([ @@ -154,7 +154,7 @@ def execute(self): self.bird_eye_view_unique_images += 1 self.previous_bird_eye_view_image = img - velocity_dim = np.full((150, 50), self.previous_speed/30) + velocity_dim = np.full((200, 66), self.previous_speed/30) new_img_vel = np.dstack((img, velocity_dim)) img = new_img_vel diff --git a/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_previous_v_broken_input_2.py b/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_previous_v_broken_input_2.py index 2ac2ae31..ae23f5fb 100644 --- a/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_previous_v_broken_input_2.py +++ b/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_previous_v_broken_input_2.py @@ -140,7 +140,7 @@ def execute(self): self.update_pose(self.pose.getPose3d()) - image_shape=(50, 150) + image_shape=(66, 200) img_base = cv2.resize(bird_eye_view_1, image_shape) AUGMENTATIONS_TEST = Compose([ @@ -154,7 +154,7 @@ def execute(self): self.bird_eye_view_unique_images += 1 self.previous_bird_eye_view_image = img - velocity_dim = np.full((150, 50), self.previous_speed/30) + velocity_dim = np.full((200, 66), self.previous_speed/30) new_img_vel = np.dstack((img, velocity_dim)) img = new_img_vel diff --git a/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_x3_previous_v_t_t-4_t-9_50_km_h.py b/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_x3_previous_v_t_t-4_t-9_50_km_h.py new file mode 100644 index 00000000..d10595b4 --- /dev/null +++ b/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_x3_previous_v_t_t-4_t-9_50_km_h.py @@ -0,0 +1,299 @@ +#!/usr/bin/python +# -*- coding: utf-8 -*- +import csv +import cv2 +import math +import numpy as np +import threading +import time +import carla +from os import path +from albumentations import ( + Compose, Normalize, RandomRain, RandomBrightness, RandomShadow, RandomSnow, RandomFog, RandomSunFlare +) +from utils.constants import PRETRAINED_MODELS_DIR, ROOT_PATH +from utils.logger import logger +from traceback import print_exc + +PRETRAINED_MODELS = ROOT_PATH + '/' + PRETRAINED_MODELS_DIR + 'CARLA/' + +from tensorflow.python.framework.errors_impl import NotFoundError +from tensorflow.python.framework.errors_impl import UnimplementedError +import tensorflow as tf + +import os +os.environ['CUDA_VISIBLE_DEVICES'] = '-1' + +#gpus = tf.config.experimental.list_physical_devices('GPU') +#for gpu in gpus: +# tf.config.experimental.set_memory_growth(gpu, True) + + +class Brain: + + def __init__(self, sensors, actuators, handler, model, config=None): + self.camera_0 = sensors.get_camera('camera_0') + self.camera_1 = sensors.get_camera('camera_1') + self.camera_2 = sensors.get_camera('camera_2') + self.camera_3 = sensors.get_camera('camera_3') + + self.cameras_first_images = [] + + self.pose = sensors.get_pose3d('pose3d_0') + + self.bird_eye_view = sensors.get_bird_eye_view('bird_eye_view_0') + + self.motors = actuators.get_motor('motors_0') + self.handler = handler + self.config = config + self.inference_times = [] + self.gpu_inference = True if tf.test.gpu_device_name() else False + + self.threshold_image = np.zeros((640, 360, 3), np.uint8) + self.color_image = np.zeros((640, 360, 3), np.uint8) + + client = carla.Client('localhost', 2000) + client.set_timeout(10.0) # seconds + world = client.get_world() + + time.sleep(5) + self.vehicle = world.get_actors().filter('vehicle.*')[0] + + if model: + if not path.exists(PRETRAINED_MODELS + model): + logger.info("File " + model + " cannot be found in " + PRETRAINED_MODELS) + logger.info("** Load TF model **") + self.net = tf.keras.models.load_model(PRETRAINED_MODELS + model) + logger.info("** Loaded TF model **") + else: + logger.info("** Brain not loaded **") + logger.info("- Models path: " + PRETRAINED_MODELS) + logger.info("- Model: " + str(model)) + + self.previous_speed = 0 + self.previous_bird_eye_view_image = 0 + self.bird_eye_view_images = 0 + self.bird_eye_view_unique_images = 0 + + self.image_1 = 0 + self.image_2 = 0 + self.image_3 = 0 + self.image_4 = 0 + self.image_5 = 0 + self.image_6 = 0 + self.image_7 = 0 + self.image_8 = 0 + self.image_9 = 0 + + self.image_1_V = 0 + self.image_2_V = 0 + self.image_3_V = 0 + self.image_4_V = 0 + self.image_5_V = 0 + self.image_6_V = 0 + self.image_7_V = 0 + self.image_8_V = 0 + self.image_9_V = 0 + + self.first_acceleration = True + + + def update_frame(self, frame_id, data): + """Update the information to be shown in one of the GUI's frames. + + Arguments: + frame_id {str} -- Id of the frame that will represent the data + data {*} -- Data to be shown in the frame. Depending on the type of frame (rgbimage, laser, pose3d, etc) + """ + if data.shape[0] != data.shape[1]: + if data.shape[0] > data.shape[1]: + difference = data.shape[0] - data.shape[1] + extra_left, extra_right = int(difference/2), int(difference/2) + extra_top, extra_bottom = 0, 0 + else: + difference = data.shape[1] - data.shape[0] + extra_left, extra_right = 0, 0 + extra_top, extra_bottom = int(difference/2), int(difference/2) + + + data = np.pad(data, ((extra_top, extra_bottom), (extra_left, extra_right), (0, 0)), mode='constant', constant_values=0) + + self.handler.update_frame(frame_id, data) + + def update_pose(self, pose_data): + self.handler.update_pose3d(pose_data) + + def execute(self): + image = self.camera_0.getImage().data + image_1 = self.camera_1.getImage().data + image_2 = self.camera_2.getImage().data + image_3 = self.camera_3.getImage().data + + bird_eye_view_1 = self.bird_eye_view.getImage(self.vehicle) + bird_eye_view_1 = cv2.cvtColor(bird_eye_view_1, cv2.COLOR_BGR2RGB) + + if self.cameras_first_images == []: + self.cameras_first_images.append(image) + self.cameras_first_images.append(image_1) + self.cameras_first_images.append(image_2) + self.cameras_first_images.append(image_3) + self.cameras_first_images.append(bird_eye_view_1) + + self.cameras_last_images = [ + image, + image_1, + image_2, + image_3, + bird_eye_view_1 + ] + + self.update_frame('frame_1', image_1) + self.update_frame('frame_2', image_2) + self.update_frame('frame_3', image_3) + + self.update_frame('frame_0', bird_eye_view_1) + + self.update_pose(self.pose.getPose3d()) + + image_shape=(50, 150) + img_base = cv2.resize(bird_eye_view_1, image_shape) + + AUGMENTATIONS_TEST = Compose([ + Normalize() + ]) + image = AUGMENTATIONS_TEST(image=img_base) + img = image["image"] + + self.bird_eye_view_images += 1 + if (self.previous_bird_eye_view_image==img).all() == False: + self.bird_eye_view_unique_images += 1 + self.previous_bird_eye_view_image = img + + if type(self.image_1) is int: + self.image_1 = img + self.image_1_V = 0 + speed = self.vehicle.get_velocity() + vehicle_speed = 3.6 * math.sqrt(speed.x**2 + speed.y**2 + speed.z**2) + self.previous_speed = vehicle_speed + elif type(self.image_2) is int: + self.image_2 = img + self.image_2_V = self.previous_speed + speed = self.vehicle.get_velocity() + vehicle_speed = 3.6 * math.sqrt(speed.x**2 + speed.y**2 + speed.z**2) + self.previous_speed = vehicle_speed + elif type(self.image_3) is int: + self.image_3 = img + self.image_3_V = self.previous_speed + speed = self.vehicle.get_velocity() + vehicle_speed = 3.6 * math.sqrt(speed.x**2 + speed.y**2 + speed.z**2) + self.previous_speed = vehicle_speed + elif type(self.image_4) is int: + self.image_4 = img + self.image_4_V = self.previous_speed + speed = self.vehicle.get_velocity() + vehicle_speed = 3.6 * math.sqrt(speed.x**2 + speed.y**2 + speed.z**2) + self.previous_speed = vehicle_speed + elif type(self.image_5) is int: + self.image_5 = img + self.image_5_V = self.previous_speed + speed = self.vehicle.get_velocity() + vehicle_speed = 3.6 * math.sqrt(speed.x**2 + speed.y**2 + speed.z**2) + self.previous_speed = vehicle_speed + elif type(self.image_6) is int: + self.image_6 = img + self.image_6_V = self.previous_speed + speed = self.vehicle.get_velocity() + vehicle_speed = 3.6 * math.sqrt(speed.x**2 + speed.y**2 + speed.z**2) + self.previous_speed = vehicle_speed + elif type(self.image_7) is int: + self.image_7 = img + self.image_7_V = self.previous_speed + speed = self.vehicle.get_velocity() + vehicle_speed = 3.6 * math.sqrt(speed.x**2 + speed.y**2 + speed.z**2) + self.previous_speed = vehicle_speed + elif type(self.image_8) is int: + self.image_8 = img + self.image_8_V = self.previous_speed + speed = self.vehicle.get_velocity() + vehicle_speed = 3.6 * math.sqrt(speed.x**2 + speed.y**2 + speed.z**2) + self.previous_speed = vehicle_speed + elif type(self.image_9) is int: + self.image_9 = img + self.image_9_V = self.previous_speed + speed = self.vehicle.get_velocity() + vehicle_speed = 3.6 * math.sqrt(speed.x**2 + speed.y**2 + speed.z**2) + self.previous_speed = vehicle_speed + else: + self.image_1 = self.image_2 + self.image_2 = self.image_3 + self.image_3 = self.image_4 + self.image_4 = self.image_5 + self.image_5 = self.image_6 + self.image_6 = self.image_7 + self.image_7 = self.image_8 + self.image_8 = self.image_9 + self.image_9 = img + + self.image_1_V = self.image_2_V + self.image_2_V = self.image_3_V + self.image_3_V = self.image_4_V + self.image_4_V = self.image_5_V + self.image_5_V = self.image_6_V + self.image_6_V = self.image_7_V + self.image_7_V = self.image_8_V + self.image_8_V = self.image_9_V + self.image_9_V = self.previous_speed + + velocity_dim_1 = np.full((150, 50), self.image_1_V/30) + image_1 = np.dstack((self.image_1, velocity_dim_1)) + + velocity_dim_4 = np.full((150, 50), self.image_4_V/30) + image_4 = np.dstack((self.image_4, velocity_dim_4)) + + velocity_dim_9 = np.full((150, 50), self.image_9_V/30) + image_9 = np.dstack((self.image_9, velocity_dim_9)) + + img = [image_1, image_4 , image_9] + + img = np.expand_dims(img, axis=0) + + start_time = time.time() + try: + prediction = self.net.predict(img, verbose=0) + self.inference_times.append(time.time() - start_time) + throttle = prediction[0][0] + steer = prediction[0][1] * (1 - (-1)) + (-1) + break_command = prediction[0][2] + speed = self.vehicle.get_velocity() + vehicle_speed = 3.6 * math.sqrt(speed.x**2 + speed.y**2 + speed.z**2) + self.previous_speed = vehicle_speed + if vehicle_speed < 50 and self.first_acceleration: + self.motors.sendThrottle(1.0) + self.motors.sendSteer(0.0) + self.motors.sendBrake(0) + else: + self.first_acceleration = False + self.motors.sendThrottle(throttle) + self.motors.sendSteer(steer) + self.motors.sendBrake(break_command) + + except NotFoundError as ex: + logger.info('Error inside brain: NotFoundError!') + logger.warning(type(ex).__name__) + print_exc() + raise Exception(ex) + except UnimplementedError as ex: + logger.info('Error inside brain: UnimplementedError!') + logger.warning(type(ex).__name__) + print_exc() + raise Exception(ex) + except Exception as ex: + logger.info('Error inside brain: Exception!') + logger.warning(type(ex).__name__) + print_exc() + raise Exception(ex) + + + + + diff --git a/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_x3_previous_v_t_t-4_t-9_broken_input.py b/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_x3_previous_v_t_t-4_t-9_broken_input.py index 373c55e8..53399b98 100644 --- a/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_x3_previous_v_t_t-4_t-9_broken_input.py +++ b/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_x3_previous_v_t_t-4_t-9_broken_input.py @@ -147,7 +147,7 @@ def execute(self): AUGMENTATIONS_TEST = Compose([ - GridDropout(p=1.0, ratio=0.9) + GridDropout(p=1.0) ]) bird_eye_view_1 = AUGMENTATIONS_TEST(image=bird_eye_view_1) diff --git a/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_x3_previous_v_t_t-4_t-9_broken_input_2.py b/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_x3_previous_v_t_t-4_t-9_broken_input_2.py index 469d3055..373c55e8 100644 --- a/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_x3_previous_v_t_t-4_t-9_broken_input_2.py +++ b/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_x3_previous_v_t_t-4_t-9_broken_input_2.py @@ -9,7 +9,7 @@ import carla from os import path from albumentations import ( - Compose, Normalize, RandomRain, RandomBrightness, RandomShadow, RandomSnow, RandomFog, RandomSunFlare, GridDropout, ChannelDropout, GaussNoise + Compose, Normalize, RandomRain, RandomBrightness, RandomShadow, RandomSnow, RandomFog, RandomSunFlare, GridDropout, ChannelDropout ) from utils.constants import PRETRAINED_MODELS_DIR, ROOT_PATH from utils.logger import logger @@ -147,8 +147,7 @@ def execute(self): AUGMENTATIONS_TEST = Compose([ - #GridDropout(p=1.0, ratio=0.5), - GaussNoise(p=1.0, var_limit=(500.0, 1500.0)) + GridDropout(p=1.0, ratio=0.9) ]) bird_eye_view_1 = AUGMENTATIONS_TEST(image=bird_eye_view_1) diff --git a/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_x3_t_t-4_t-9.py b/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_x3_t_t-4_t-9.py index 8b895393..f31c666b 100644 --- a/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_x3_t_t-4_t-9.py +++ b/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_x3_t_t-4_t-9.py @@ -170,9 +170,11 @@ def execute(self): self.image_8 = img elif type(self.image_9) is int: self.image_9 = img + elif type(self.image_10) is int: + self.image_10 = img else: self.bird_eye_view_images += 1 - if (self.image_9==img).all() == False: + if (self.image_10==img).all() == False: self.bird_eye_view_unique_images += 1 self.image_1 = self.image_2 self.image_2 = self.image_3 @@ -182,9 +184,11 @@ def execute(self): self.image_6 = self.image_7 self.image_7 = self.image_8 self.image_8 = self.image_9 - self.image_9 = img + self.image_9 = self.image_10 + self.image_10 = img - img = [self.image_1, self.image_4, self.image_9] + #img = [self.image_1, self.image_4, self.image_9] + img = [self.image_1, self.image_5, self.image_10] img = np.expand_dims(img, axis=0) start_time = time.time() diff --git a/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_x3_t_t-4_t-9_50_km_h.py b/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_x3_t_t-4_t-9_50_km_h.py new file mode 100644 index 00000000..3f018dec --- /dev/null +++ b/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_x3_t_t-4_t-9_50_km_h.py @@ -0,0 +1,228 @@ +#!/usr/bin/python +# -*- coding: utf-8 -*- +import csv +import cv2 +import math +import numpy as np +import threading +import time +import carla +from os import path +from albumentations import ( + Compose, Normalize, RandomRain, RandomBrightness, RandomShadow, RandomSnow, RandomFog, RandomSunFlare +) +from utils.constants import PRETRAINED_MODELS_DIR, ROOT_PATH +from utils.logger import logger +from traceback import print_exc + +PRETRAINED_MODELS = ROOT_PATH + '/' + PRETRAINED_MODELS_DIR + 'CARLA/' + +from tensorflow.python.framework.errors_impl import NotFoundError +from tensorflow.python.framework.errors_impl import UnimplementedError +import tensorflow as tf + +import os +os.environ['CUDA_VISIBLE_DEVICES'] = '-1' + +#gpus = tf.config.experimental.list_physical_devices('GPU') +#for gpu in gpus: +# tf.config.experimental.set_memory_growth(gpu, True) + + + +class Brain: + + def __init__(self, sensors, actuators, handler, model, config=None): + self.camera_0 = sensors.get_camera('camera_0') + self.camera_1 = sensors.get_camera('camera_1') + self.camera_2 = sensors.get_camera('camera_2') + self.camera_3 = sensors.get_camera('camera_3') + + self.cameras_first_images = [] + + self.pose = sensors.get_pose3d('pose3d_0') + + self.bird_eye_view = sensors.get_bird_eye_view('bird_eye_view_0') + + self.motors = actuators.get_motor('motors_0') + self.handler = handler + self.config = config + self.inference_times = [] + self.gpu_inference = True if tf.test.gpu_device_name() else False + + self.threshold_image = np.zeros((640, 360, 3), np.uint8) + self.color_image = np.zeros((640, 360, 3), np.uint8) + + client = carla.Client('localhost', 2000) + client.set_timeout(10.0) # seconds + world = client.get_world() + + time.sleep(5) + self.vehicle = world.get_actors().filter('vehicle.*')[0] + + if model: + if not path.exists(PRETRAINED_MODELS + model): + logger.info("File " + model + " cannot be found in " + PRETRAINED_MODELS) + logger.info("** Load TF model **") + self.net = tf.keras.models.load_model(PRETRAINED_MODELS + model) + logger.info("** Loaded TF model **") + else: + logger.info("** Brain not loaded **") + logger.info("- Models path: " + PRETRAINED_MODELS) + logger.info("- Model: " + str(model)) + + self.image_1 = 0 + self.image_2 = 0 + self.image_3 = 0 + self.image_4 = 0 + self.image_5 = 0 + self.image_6 = 0 + self.image_7 = 0 + self.image_8 = 0 + self.image_9 = 0 + self.image_10 = 0 + + self.bird_eye_view_images = 0 + self.bird_eye_view_unique_images = 0 + + self.first_acceleration = True + + + def update_frame(self, frame_id, data): + """Update the information to be shown in one of the GUI's frames. + + Arguments: + frame_id {str} -- Id of the frame that will represent the data + data {*} -- Data to be shown in the frame. Depending on the type of frame (rgbimage, laser, pose3d, etc) + """ + if data.shape[0] != data.shape[1]: + if data.shape[0] > data.shape[1]: + difference = data.shape[0] - data.shape[1] + extra_left, extra_right = int(difference/2), int(difference/2) + extra_top, extra_bottom = 0, 0 + else: + difference = data.shape[1] - data.shape[0] + extra_left, extra_right = 0, 0 + extra_top, extra_bottom = int(difference/2), int(difference/2) + + + data = np.pad(data, ((extra_top, extra_bottom), (extra_left, extra_right), (0, 0)), mode='constant', constant_values=0) + + self.handler.update_frame(frame_id, data) + + def update_pose(self, pose_data): + self.handler.update_pose3d(pose_data) + + def execute(self): + image = self.camera_0.getImage().data + image_1 = self.camera_1.getImage().data + image_2 = self.camera_2.getImage().data + image_3 = self.camera_3.getImage().data + + bird_eye_view_1 = self.bird_eye_view.getImage(self.vehicle) + bird_eye_view_1 = cv2.cvtColor(bird_eye_view_1, cv2.COLOR_BGR2RGB) + + if self.cameras_first_images == []: + self.cameras_first_images.append(image) + self.cameras_first_images.append(image_1) + self.cameras_first_images.append(image_2) + self.cameras_first_images.append(image_3) + self.cameras_first_images.append(bird_eye_view_1) + + self.cameras_last_images = [ + image, + image_1, + image_2, + image_3, + bird_eye_view_1 + ] + + self.update_frame('frame_1', image_1) + self.update_frame('frame_2', image_2) + self.update_frame('frame_3', image_3) + + self.update_frame('frame_0', bird_eye_view_1) + + self.update_pose(self.pose.getPose3d()) + + image_shape=(50, 150) + img_base = cv2.resize(bird_eye_view_1, image_shape) + + AUGMENTATIONS_TEST = Compose([ + Normalize() + ]) + image = AUGMENTATIONS_TEST(image=img_base) + img = image["image"] + + if type(self.image_1) is int: + self.image_1 = img + elif type(self.image_2) is int: + self.image_2 = img + elif type(self.image_3) is int: + self.image_3 = img + elif type(self.image_4) is int: + self.image_4 = img + elif type(self.image_5) is int: + self.image_5 = img + elif type(self.image_6) is int: + self.image_6 = img + elif type(self.image_7) is int: + self.image_7 = img + elif type(self.image_8) is int: + self.image_8 = img + elif type(self.image_9) is int: + self.image_9 = img + elif type(self.image_10) is int: + self.image_10 = img + else: + self.bird_eye_view_images += 1 + if (self.image_10==img).all() == False: + self.bird_eye_view_unique_images += 1 + self.image_1 = self.image_2 + self.image_2 = self.image_3 + self.image_3 = self.image_4 + self.image_4 = self.image_5 + self.image_5 = self.image_6 + self.image_6 = self.image_7 + self.image_7 = self.image_8 + self.image_8 = self.image_9 + self.image_9 = self.image_10 + self.image_10 = img + + img = [self.image_1, self.image_5, self.image_10] + img = np.expand_dims(img, axis=0) + + start_time = time.time() + try: + prediction = self.net.predict(img, verbose=0) + self.inference_times.append(time.time() - start_time) + throttle = prediction[0][0] + steer = prediction[0][1] * (1 - (-1)) + (-1) + break_command = prediction[0][2] + speed = self.vehicle.get_velocity() + vehicle_speed = 3.6 * math.sqrt(speed.x**2 + speed.y**2 + speed.z**2) + + if vehicle_speed < 50 and self.first_acceleration: + self.motors.sendThrottle(1.0) + self.motors.sendSteer(0.0) + self.motors.sendBrake(0) + else: + self.motors.sendThrottle(throttle) + self.motors.sendSteer(steer) + self.motors.sendBrake(break_command) + + except NotFoundError as ex: + logger.info('Error inside brain: NotFoundError!') + logger.warning(type(ex).__name__) + print_exc() + raise Exception(ex) + except UnimplementedError as ex: + logger.info('Error inside brain: UnimplementedError!') + logger.warning(type(ex).__name__) + print_exc() + raise Exception(ex) + except Exception as ex: + logger.info('Error inside brain: Exception!') + logger.warning(type(ex).__name__) + print_exc() + raise Exception(ex) \ No newline at end of file diff --git a/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_x3_t_t-4_t-9_70_km_h.py b/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_x3_t_t-4_t-9_70_km_h.py index 93ce6163..9ee732b9 100644 --- a/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_x3_t_t-4_t-9_70_km_h.py +++ b/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_x3_t_t-4_t-9_70_km_h.py @@ -172,9 +172,11 @@ def execute(self): self.image_8 = img elif type(self.image_9) is int: self.image_9 = img + elif type(self.image_10) is int: + self.image_10 = img else: self.bird_eye_view_images += 1 - if (self.image_9==img).all() == False: + if (self.image_10==img).all() == False: self.bird_eye_view_unique_images += 1 self.image_1 = self.image_2 self.image_2 = self.image_3 @@ -184,9 +186,10 @@ def execute(self): self.image_6 = self.image_7 self.image_7 = self.image_8 self.image_8 = self.image_9 - self.image_9 = img + self.image_9 = self.image_10 + self.image_10 = img - img = [self.image_1, self.image_4, self.image_9] + img = [self.image_1, self.image_5, self.image_10] img = np.expand_dims(img, axis=0) start_time = time.time() diff --git a/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_x3_t_t-4_t-9_V_MAX_30.py b/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_x3_t_t-4_t-9_V_MAX_30.py index db355b88..9ceb5b7b 100644 --- a/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_x3_t_t-4_t-9_V_MAX_30.py +++ b/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_x3_t_t-4_t-9_V_MAX_30.py @@ -239,7 +239,7 @@ def execute(self): self.motors.sendSteer(0.0) self.motors.sendBrake(0) else: - self.motors.sendThrottle(0.75) + self.motors.sendThrottle(throttle) self.motors.sendSteer(steer) self.motors.sendBrake(break_command) diff --git a/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_x3_t_t_10_t_20.py b/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_x3_t_t_10_t_20.py new file mode 100644 index 00000000..ad5dc033 --- /dev/null +++ b/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_x3_t_t_10_t_20.py @@ -0,0 +1,280 @@ +#!/usr/bin/python +# -*- coding: utf-8 -*- +import csv +import cv2 +import math +import numpy as np +import threading +import time +import carla +from os import path +from albumentations import ( + Compose, Normalize, RandomRain, RandomBrightness, RandomShadow, RandomSnow, RandomFog, RandomSunFlare +) +from utils.constants import PRETRAINED_MODELS_DIR, ROOT_PATH +from utils.logger import logger +from traceback import print_exc + +PRETRAINED_MODELS = ROOT_PATH + '/' + PRETRAINED_MODELS_DIR + 'CARLA/' + +from tensorflow.python.framework.errors_impl import NotFoundError +from tensorflow.python.framework.errors_impl import UnimplementedError +import tensorflow as tf + +import os +os.environ['CUDA_VISIBLE_DEVICES'] = '-1' + +#gpus = tf.config.experimental.list_physical_devices('GPU') +#for gpu in gpus: +# tf.config.experimental.set_memory_growth(gpu, True) + + + +class Brain: + + def __init__(self, sensors, actuators, handler, model, config=None): + self.camera_0 = sensors.get_camera('camera_0') + self.camera_1 = sensors.get_camera('camera_1') + self.camera_2 = sensors.get_camera('camera_2') + self.camera_3 = sensors.get_camera('camera_3') + + self.cameras_first_images = [] + + self.pose = sensors.get_pose3d('pose3d_0') + + self.bird_eye_view = sensors.get_bird_eye_view('bird_eye_view_0') + + self.motors = actuators.get_motor('motors_0') + self.handler = handler + self.config = config + self.inference_times = [] + self.gpu_inference = True if tf.test.gpu_device_name() else False + + self.threshold_image = np.zeros((640, 360, 3), np.uint8) + self.color_image = np.zeros((640, 360, 3), np.uint8) + + client = carla.Client('localhost', 2000) + client.set_timeout(10.0) # seconds + world = client.get_world() + + time.sleep(5) + self.vehicle = world.get_actors().filter('vehicle.*')[0] + + if model: + if not path.exists(PRETRAINED_MODELS + model): + logger.info("File " + model + " cannot be found in " + PRETRAINED_MODELS) + logger.info("** Load TF model **") + self.net = tf.keras.models.load_model(PRETRAINED_MODELS + model) + logger.info("** Loaded TF model **") + else: + logger.info("** Brain not loaded **") + logger.info("- Models path: " + PRETRAINED_MODELS) + logger.info("- Model: " + str(model)) + + self.image_1 = 0 + self.image_2 = 0 + self.image_3 = 0 + self.image_4 = 0 + self.image_5 = 0 + self.image_6 = 0 + self.image_7 = 0 + self.image_8 = 0 + self.image_9 = 0 + self.image_10 = 0 + + self.image_11 = 0 + self.image_12 = 0 + self.image_13 = 0 + self.image_14 = 0 + self.image_15 = 0 + self.image_16 = 0 + self.image_17 = 0 + self.image_18 = 0 + self.image_19 = 0 + self.image_20 = 0 + + self.bird_eye_view_images = 0 + self.bird_eye_view_unique_images = 0 + + + def update_frame(self, frame_id, data): + """Update the information to be shown in one of the GUI's frames. + + Arguments: + frame_id {str} -- Id of the frame that will represent the data + data {*} -- Data to be shown in the frame. Depending on the type of frame (rgbimage, laser, pose3d, etc) + """ + if data.shape[0] != data.shape[1]: + if data.shape[0] > data.shape[1]: + difference = data.shape[0] - data.shape[1] + extra_left, extra_right = int(difference/2), int(difference/2) + extra_top, extra_bottom = 0, 0 + else: + difference = data.shape[1] - data.shape[0] + extra_left, extra_right = 0, 0 + extra_top, extra_bottom = int(difference/2), int(difference/2) + + + data = np.pad(data, ((extra_top, extra_bottom), (extra_left, extra_right), (0, 0)), mode='constant', constant_values=0) + + self.handler.update_frame(frame_id, data) + + def update_pose(self, pose_data): + self.handler.update_pose3d(pose_data) + + def execute(self): + image = self.camera_0.getImage().data + image_1 = self.camera_1.getImage().data + image_2 = self.camera_2.getImage().data + image_3 = self.camera_3.getImage().data + + bird_eye_view_1 = self.bird_eye_view.getImage(self.vehicle) + bird_eye_view_1 = cv2.cvtColor(bird_eye_view_1, cv2.COLOR_BGR2RGB) + + if self.cameras_first_images == []: + self.cameras_first_images.append(image) + self.cameras_first_images.append(image_1) + self.cameras_first_images.append(image_2) + self.cameras_first_images.append(image_3) + self.cameras_first_images.append(bird_eye_view_1) + + self.cameras_last_images = [ + image, + image_1, + image_2, + image_3, + bird_eye_view_1 + ] + + self.update_frame('frame_1', image_1) + self.update_frame('frame_2', image_2) + self.update_frame('frame_3', image_3) + + self.update_frame('frame_0', bird_eye_view_1) + + self.update_pose(self.pose.getPose3d()) + + image_shape=(50, 150) + img_base = cv2.resize(bird_eye_view_1, image_shape) + + AUGMENTATIONS_TEST = Compose([ + Normalize() + ]) + image = AUGMENTATIONS_TEST(image=img_base) + img = image["image"] + + if type(self.image_1) is int: + self.image_1 = img + elif type(self.image_2) is int: + self.image_2 = img + elif type(self.image_3) is int: + self.image_3 = img + elif type(self.image_4) is int: + self.image_4 = img + elif type(self.image_5) is int: + self.image_5 = img + elif type(self.image_6) is int: + self.image_6 = img + elif type(self.image_7) is int: + self.image_7 = img + elif type(self.image_8) is int: + self.image_8 = img + elif type(self.image_9) is int: + self.image_9 = img + + elif type(self.image_10) is int: + self.image_10 = img + elif type(self.image_11) is int: + self.image_11 = img + elif type(self.image_12) is int: + self.image_12 = img + elif type(self.image_13) is int: + self.image_13 = img + elif type(self.image_14) is int: + self.image_14 = img + elif type(self.image_15) is int: + self.image_15 = img + elif type(self.image_16) is int: + self.image_16 = img + elif type(self.image_17) is int: + self.image_17 = img + elif type(self.image_18) is int: + self.image_18 = img + elif type(self.image_19) is int: + self.image_19 = img + elif type(self.image_20) is int: + self.image_20 = img + else: + self.bird_eye_view_images += 1 + if (self.image_20==img).all() == False: + self.bird_eye_view_unique_images += 1 + self.image_1 = self.image_2 + self.image_2 = self.image_3 + self.image_3 = self.image_4 + self.image_4 = self.image_5 + self.image_5 = self.image_6 + self.image_6 = self.image_7 + self.image_7 = self.image_8 + self.image_8 = self.image_9 + self.image_9 = self.image_10 + + self.image_10 = self.image_11 + self.image_11 = self.image_12 + self.image_12 = self.image_13 + self.image_13 = self.image_14 + self.image_14 = self.image_15 + self.image_15 = self.image_16 + self.image_16 = self.image_17 + self.image_17 = self.image_18 + self.image_18 = self.image_19 + + self.image_19 = self.image_20 + self.image_20 = img + + + #img = [self.image_1, self.image_4, self.image_9] + #img = [self.image_1, self.image_4, self.image_9, self.image_14, self.image_19, self.image_24, self.image_29, self.image_34, self.image_39] + + + img = [self.image_1, self.image_10, self.image_20] + img = np.expand_dims(img, axis=0) + + start_time = time.time() + try: + prediction = self.net.predict(img, verbose=0) + self.inference_times.append(time.time() - start_time) + throttle = prediction[0][0] + steer = prediction[0][1] * (1 - (-1)) + (-1) + break_command = prediction[0][2] + speed = self.vehicle.get_velocity() + vehicle_speed = 3.6 * math.sqrt(speed.x**2 + speed.y**2 + speed.z**2) + + if vehicle_speed > 30: + self.motors.sendThrottle(0.0) + self.motors.sendSteer(steer) + self.motors.sendBrake(break_command) + else: + if vehicle_speed < 5: + self.motors.sendThrottle(1.0) + self.motors.sendSteer(0.0) + self.motors.sendBrake(0) + else: + self.motors.sendThrottle(0.75) + self.motors.sendSteer(steer) + self.motors.sendBrake(break_command) + + except NotFoundError as ex: + logger.info('Error inside brain: NotFoundError!') + logger.warning(type(ex).__name__) + print_exc() + raise Exception(ex) + except UnimplementedError as ex: + logger.info('Error inside brain: UnimplementedError!') + logger.warning(type(ex).__name__) + print_exc() + raise Exception(ex) + except Exception as ex: + logger.info('Error inside brain: Exception!') + logger.warning(type(ex).__name__) + print_exc() + raise Exception(ex) \ No newline at end of file diff --git a/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_x3_t_t_1_t_2.py b/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_x3_t_t_1_t_2.py new file mode 100644 index 00000000..f80cd7cb --- /dev/null +++ b/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_x3_t_t_1_t_2.py @@ -0,0 +1,205 @@ +#!/usr/bin/python +# -*- coding: utf-8 -*- +import csv +import cv2 +import math +import numpy as np +import threading +import time +import carla +from os import path +from albumentations import ( + Compose, Normalize, RandomRain, RandomBrightness, RandomShadow, RandomSnow, RandomFog, RandomSunFlare +) +from utils.constants import PRETRAINED_MODELS_DIR, ROOT_PATH +from utils.logger import logger +from traceback import print_exc + +PRETRAINED_MODELS = ROOT_PATH + '/' + PRETRAINED_MODELS_DIR + 'CARLA/' + +from tensorflow.python.framework.errors_impl import NotFoundError +from tensorflow.python.framework.errors_impl import UnimplementedError +import tensorflow as tf + +import os +os.environ['CUDA_VISIBLE_DEVICES'] = '-1' + +#gpus = tf.config.experimental.list_physical_devices('GPU') +#for gpu in gpus: +# tf.config.experimental.set_memory_growth(gpu, True) + + + +class Brain: + + def __init__(self, sensors, actuators, handler, model, config=None): + self.camera_0 = sensors.get_camera('camera_0') + self.camera_1 = sensors.get_camera('camera_1') + self.camera_2 = sensors.get_camera('camera_2') + self.camera_3 = sensors.get_camera('camera_3') + + self.cameras_first_images = [] + + self.pose = sensors.get_pose3d('pose3d_0') + + self.bird_eye_view = sensors.get_bird_eye_view('bird_eye_view_0') + + self.motors = actuators.get_motor('motors_0') + self.handler = handler + self.config = config + self.inference_times = [] + self.gpu_inference = True if tf.test.gpu_device_name() else False + + self.threshold_image = np.zeros((640, 360, 3), np.uint8) + self.color_image = np.zeros((640, 360, 3), np.uint8) + + client = carla.Client('localhost', 2000) + client.set_timeout(10.0) # seconds + world = client.get_world() + + time.sleep(5) + self.vehicle = world.get_actors().filter('vehicle.*')[0] + + if model: + if not path.exists(PRETRAINED_MODELS + model): + logger.info("File " + model + " cannot be found in " + PRETRAINED_MODELS) + logger.info("** Load TF model **") + self.net = tf.keras.models.load_model(PRETRAINED_MODELS + model) + logger.info("** Loaded TF model **") + else: + logger.info("** Brain not loaded **") + logger.info("- Models path: " + PRETRAINED_MODELS) + logger.info("- Model: " + str(model)) + + self.image_1 = 0 + self.image_2 = 0 + self.image_3 = 0 + + self.bird_eye_view_images = 0 + self.bird_eye_view_unique_images = 0 + + + def update_frame(self, frame_id, data): + """Update the information to be shown in one of the GUI's frames. + + Arguments: + frame_id {str} -- Id of the frame that will represent the data + data {*} -- Data to be shown in the frame. Depending on the type of frame (rgbimage, laser, pose3d, etc) + """ + if data.shape[0] != data.shape[1]: + if data.shape[0] > data.shape[1]: + difference = data.shape[0] - data.shape[1] + extra_left, extra_right = int(difference/2), int(difference/2) + extra_top, extra_bottom = 0, 0 + else: + difference = data.shape[1] - data.shape[0] + extra_left, extra_right = 0, 0 + extra_top, extra_bottom = int(difference/2), int(difference/2) + + + data = np.pad(data, ((extra_top, extra_bottom), (extra_left, extra_right), (0, 0)), mode='constant', constant_values=0) + + self.handler.update_frame(frame_id, data) + + def update_pose(self, pose_data): + self.handler.update_pose3d(pose_data) + + def execute(self): + image = self.camera_0.getImage().data + image_1 = self.camera_1.getImage().data + image_2 = self.camera_2.getImage().data + image_3 = self.camera_3.getImage().data + + bird_eye_view_1 = self.bird_eye_view.getImage(self.vehicle) + bird_eye_view_1 = cv2.cvtColor(bird_eye_view_1, cv2.COLOR_BGR2RGB) + + if self.cameras_first_images == []: + self.cameras_first_images.append(image) + self.cameras_first_images.append(image_1) + self.cameras_first_images.append(image_2) + self.cameras_first_images.append(image_3) + self.cameras_first_images.append(bird_eye_view_1) + + self.cameras_last_images = [ + image, + image_1, + image_2, + image_3, + bird_eye_view_1 + ] + + self.update_frame('frame_1', image_1) + self.update_frame('frame_2', image_2) + self.update_frame('frame_3', image_3) + + self.update_frame('frame_0', bird_eye_view_1) + + self.update_pose(self.pose.getPose3d()) + + image_shape=(50, 150) + img_base = cv2.resize(bird_eye_view_1, image_shape) + + AUGMENTATIONS_TEST = Compose([ + Normalize() + ]) + image = AUGMENTATIONS_TEST(image=img_base) + img = image["image"] + + if type(self.image_1) is int: + self.image_1 = img + elif type(self.image_2) is int: + self.image_2 = img + elif type(self.image_3) is int: + self.image_3 = img + else: + self.bird_eye_view_images += 1 + if (self.image_3==img).all() == False: + self.bird_eye_view_unique_images += 1 + self.image_1 = self.image_2 + self.image_2 = self.image_3 + self.image_3 = img + + #img = [self.image_1, self.image_4, self.image_9] + img = [self.image_1, self.image_2, self.image_3] + img = np.expand_dims(img, axis=0) + + start_time = time.time() + try: + prediction = self.net.predict(img, verbose=0) + self.inference_times.append(time.time() - start_time) + #print(prediction) + throttle = prediction[0][0] + steer = prediction[0][1] * (1 - (-1)) + (-1) + break_command = prediction[0][2] + speed = self.vehicle.get_velocity() + vehicle_speed = 3.6 * math.sqrt(speed.x**2 + speed.y**2 + speed.z**2) + + if vehicle_speed > 30: + self.motors.sendThrottle(0.0) + self.motors.sendSteer(steer) + self.motors.sendBrake(break_command) + else: + if vehicle_speed < 5: + self.motors.sendThrottle(1.0) + self.motors.sendSteer(0.0) + self.motors.sendBrake(0) + else: + self.motors.sendThrottle(throttle) + self.motors.sendSteer(steer) + self.motors.sendBrake(break_command) + + except NotFoundError as ex: + logger.info('Error inside brain: NotFoundError!') + logger.warning(type(ex).__name__) + print_exc() + raise Exception(ex) + except UnimplementedError as ex: + logger.info('Error inside brain: UnimplementedError!') + logger.warning(type(ex).__name__) + print_exc() + raise Exception(ex) + except Exception as ex: + logger.info('Error inside brain: Exception!') + logger.warning(type(ex).__name__) + print_exc() + raise Exception(ex) \ No newline at end of file diff --git a/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_x3_t_t_20_t_40.py b/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_x3_t_t_20_t_40.py new file mode 100644 index 00000000..5acec599 --- /dev/null +++ b/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_x3_t_t_20_t_40.py @@ -0,0 +1,359 @@ +#!/usr/bin/python +# -*- coding: utf-8 -*- +import csv +import cv2 +import math +import numpy as np +import threading +import time +import carla +from os import path +from albumentations import ( + Compose, Normalize, RandomRain, RandomBrightness, RandomShadow, RandomSnow, RandomFog, RandomSunFlare +) +from utils.constants import PRETRAINED_MODELS_DIR, ROOT_PATH +from utils.logger import logger +from traceback import print_exc + +PRETRAINED_MODELS = ROOT_PATH + '/' + PRETRAINED_MODELS_DIR + 'CARLA/' + +from tensorflow.python.framework.errors_impl import NotFoundError +from tensorflow.python.framework.errors_impl import UnimplementedError +import tensorflow as tf + +import os +os.environ['CUDA_VISIBLE_DEVICES'] = '-1' + +#gpus = tf.config.experimental.list_physical_devices('GPU') +#for gpu in gpus: +# tf.config.experimental.set_memory_growth(gpu, True) + + + +class Brain: + + def __init__(self, sensors, actuators, handler, model, config=None): + self.camera_0 = sensors.get_camera('camera_0') + self.camera_1 = sensors.get_camera('camera_1') + self.camera_2 = sensors.get_camera('camera_2') + self.camera_3 = sensors.get_camera('camera_3') + + self.cameras_first_images = [] + + self.pose = sensors.get_pose3d('pose3d_0') + + self.bird_eye_view = sensors.get_bird_eye_view('bird_eye_view_0') + + self.motors = actuators.get_motor('motors_0') + self.handler = handler + self.config = config + self.inference_times = [] + self.gpu_inference = True if tf.test.gpu_device_name() else False + + self.threshold_image = np.zeros((640, 360, 3), np.uint8) + self.color_image = np.zeros((640, 360, 3), np.uint8) + + client = carla.Client('localhost', 2000) + client.set_timeout(10.0) # seconds + world = client.get_world() + + time.sleep(5) + self.vehicle = world.get_actors().filter('vehicle.*')[0] + + if model: + if not path.exists(PRETRAINED_MODELS + model): + logger.info("File " + model + " cannot be found in " + PRETRAINED_MODELS) + logger.info("** Load TF model **") + self.net = tf.keras.models.load_model(PRETRAINED_MODELS + model) + logger.info("** Loaded TF model **") + else: + logger.info("** Brain not loaded **") + logger.info("- Models path: " + PRETRAINED_MODELS) + logger.info("- Model: " + str(model)) + + self.image_1 = 0 + self.image_2 = 0 + self.image_3 = 0 + self.image_4 = 0 + self.image_5 = 0 + self.image_6 = 0 + self.image_7 = 0 + self.image_8 = 0 + self.image_9 = 0 + self.image_10 = 0 + + self.image_11 = 0 + self.image_12 = 0 + self.image_13 = 0 + self.image_14 = 0 + self.image_15 = 0 + self.image_16 = 0 + self.image_17 = 0 + self.image_18 = 0 + self.image_19 = 0 + self.image_20 = 0 + + self.image_21 = 0 + self.image_22 = 0 + self.image_23 = 0 + self.image_24 = 0 + self.image_25 = 0 + self.image_26 = 0 + self.image_27 = 0 + self.image_28 = 0 + self.image_29 = 0 + self.image_30 = 0 + + self.image_31 = 0 + self.image_32 = 0 + self.image_33 = 0 + self.image_34 = 0 + self.image_35 = 0 + self.image_36 = 0 + self.image_37 = 0 + self.image_38 = 0 + self.image_39 = 0 + self.image_40 = 0 + + self.bird_eye_view_images = 0 + self.bird_eye_view_unique_images = 0 + + + def update_frame(self, frame_id, data): + """Update the information to be shown in one of the GUI's frames. + + Arguments: + frame_id {str} -- Id of the frame that will represent the data + data {*} -- Data to be shown in the frame. Depending on the type of frame (rgbimage, laser, pose3d, etc) + """ + if data.shape[0] != data.shape[1]: + if data.shape[0] > data.shape[1]: + difference = data.shape[0] - data.shape[1] + extra_left, extra_right = int(difference/2), int(difference/2) + extra_top, extra_bottom = 0, 0 + else: + difference = data.shape[1] - data.shape[0] + extra_left, extra_right = 0, 0 + extra_top, extra_bottom = int(difference/2), int(difference/2) + + + data = np.pad(data, ((extra_top, extra_bottom), (extra_left, extra_right), (0, 0)), mode='constant', constant_values=0) + + self.handler.update_frame(frame_id, data) + + def update_pose(self, pose_data): + self.handler.update_pose3d(pose_data) + + def execute(self): + image = self.camera_0.getImage().data + image_1 = self.camera_1.getImage().data + image_2 = self.camera_2.getImage().data + image_3 = self.camera_3.getImage().data + + bird_eye_view_1 = self.bird_eye_view.getImage(self.vehicle) + bird_eye_view_1 = cv2.cvtColor(bird_eye_view_1, cv2.COLOR_BGR2RGB) + + if self.cameras_first_images == []: + self.cameras_first_images.append(image) + self.cameras_first_images.append(image_1) + self.cameras_first_images.append(image_2) + self.cameras_first_images.append(image_3) + self.cameras_first_images.append(bird_eye_view_1) + + self.cameras_last_images = [ + image, + image_1, + image_2, + image_3, + bird_eye_view_1 + ] + + self.update_frame('frame_1', image_1) + self.update_frame('frame_2', image_2) + self.update_frame('frame_3', image_3) + + self.update_frame('frame_0', bird_eye_view_1) + + self.update_pose(self.pose.getPose3d()) + + image_shape=(50, 150) + img_base = cv2.resize(bird_eye_view_1, image_shape) + + AUGMENTATIONS_TEST = Compose([ + Normalize() + ]) + image = AUGMENTATIONS_TEST(image=img_base) + img = image["image"] + + if type(self.image_1) is int: + self.image_1 = img + elif type(self.image_2) is int: + self.image_2 = img + elif type(self.image_3) is int: + self.image_3 = img + elif type(self.image_4) is int: + self.image_4 = img + elif type(self.image_5) is int: + self.image_5 = img + elif type(self.image_6) is int: + self.image_6 = img + elif type(self.image_7) is int: + self.image_7 = img + elif type(self.image_8) is int: + self.image_8 = img + elif type(self.image_9) is int: + self.image_9 = img + + elif type(self.image_10) is int: + self.image_10 = img + elif type(self.image_11) is int: + self.image_11 = img + elif type(self.image_12) is int: + self.image_12 = img + elif type(self.image_13) is int: + self.image_13 = img + elif type(self.image_14) is int: + self.image_14 = img + elif type(self.image_15) is int: + self.image_15 = img + elif type(self.image_16) is int: + self.image_16 = img + elif type(self.image_17) is int: + self.image_17 = img + elif type(self.image_18) is int: + self.image_18 = img + elif type(self.image_19) is int: + self.image_19 = img + elif type(self.image_20) is int: + self.image_20 = img + elif type(self.image_21) is int: + self.image_21 = img + elif type(self.image_22) is int: + self.image_22 = img + elif type(self.image_23) is int: + self.image_23 = img + elif type(self.image_24) is int: + self.image_24 = img + elif type(self.image_25) is int: + self.image_25 = img + elif type(self.image_26) is int: + self.image_26 = img + elif type(self.image_27) is int: + self.image_27 = img + elif type(self.image_28) is int: + self.image_28 = img + elif type(self.image_29) is int: + self.image_29 = img + elif type(self.image_30) is int: + self.image_30 = img + elif type(self.image_31) is int: + self.image_31 = img + elif type(self.image_32) is int: + self.image_32 = img + elif type(self.image_33) is int: + self.image_33 = img + elif type(self.image_34) is int: + self.image_34 = img + elif type(self.image_35) is int: + self.image_35 = img + elif type(self.image_36) is int: + self.image_36 = img + elif type(self.image_37) is int: + self.image_37 = img + elif type(self.image_38) is int: + self.image_38 = img + elif type(self.image_39) is int: + self.image_39 = img + elif type(self.image_40) is int: + self.image_40 = img + else: + self.bird_eye_view_images += 1 + if (self.image_40==img).all() == False: + self.bird_eye_view_unique_images += 1 + self.image_1 = self.image_2 + self.image_2 = self.image_3 + self.image_3 = self.image_4 + self.image_4 = self.image_5 + self.image_5 = self.image_6 + self.image_6 = self.image_7 + self.image_7 = self.image_8 + self.image_8 = self.image_9 + self.image_9 = self.image_10 + + self.image_10 = self.image_11 + self.image_11 = self.image_12 + self.image_12 = self.image_13 + self.image_13 = self.image_14 + self.image_14 = self.image_15 + self.image_15 = self.image_16 + self.image_16 = self.image_17 + self.image_17 = self.image_18 + self.image_18 = self.image_19 + + self.image_19 = self.image_20 + self.image_20 = self.image_21 + self.image_21 = self.image_22 + self.image_22 = self.image_23 + self.image_23 = self.image_24 + self.image_24 = self.image_25 + self.image_25 = self.image_26 + self.image_26 = self.image_27 + self.image_27 = self.image_28 + + self.image_28 = self.image_29 + self.image_29 = self.image_30 + self.image_30 = self.image_31 + self.image_31 = self.image_32 + self.image_32 = self.image_33 + self.image_33 = self.image_34 + self.image_34 = self.image_35 + self.image_35 = self.image_36 + self.image_36 = self.image_37 + + self.image_37 = self.image_38 + self.image_38 = self.image_39 + self.image_39 = self.image_40 + self.image_40 = img + + img = [self.image_1, self.image_20, self.image_40] + img = np.expand_dims(img, axis=0) + + start_time = time.time() + try: + prediction = self.net.predict(img, verbose=0) + self.inference_times.append(time.time() - start_time) + throttle = prediction[0][0] + steer = prediction[0][1] * (1 - (-1)) + (-1) + break_command = prediction[0][2] + speed = self.vehicle.get_velocity() + vehicle_speed = 3.6 * math.sqrt(speed.x**2 + speed.y**2 + speed.z**2) + + if vehicle_speed > 30: + self.motors.sendThrottle(0.0) + self.motors.sendSteer(steer) + self.motors.sendBrake(break_command) + else: + if vehicle_speed < 5: + self.motors.sendThrottle(1.0) + self.motors.sendSteer(0.0) + self.motors.sendBrake(0) + else: + self.motors.sendThrottle(0.75) + self.motors.sendSteer(steer) + self.motors.sendBrake(break_command) + + except NotFoundError as ex: + logger.info('Error inside brain: NotFoundError!') + logger.warning(type(ex).__name__) + print_exc() + raise Exception(ex) + except UnimplementedError as ex: + logger.info('Error inside brain: UnimplementedError!') + logger.warning(type(ex).__name__) + print_exc() + raise Exception(ex) + except Exception as ex: + logger.info('Error inside brain: Exception!') + logger.warning(type(ex).__name__) + print_exc() + raise Exception(ex) \ No newline at end of file diff --git a/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_x5_V_MAX_30.py b/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_x5_V_MAX_30.py new file mode 100644 index 00000000..f5db3576 --- /dev/null +++ b/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_x5_V_MAX_30.py @@ -0,0 +1,275 @@ +#!/usr/bin/python +# -*- coding: utf-8 -*- +import csv +import cv2 +import math +import numpy as np +import threading +import time +import carla +from os import path +from albumentations import ( + Compose, Normalize, RandomRain, RandomBrightness, RandomShadow, RandomSnow, RandomFog, RandomSunFlare +) +from utils.constants import PRETRAINED_MODELS_DIR, ROOT_PATH +from utils.logger import logger +from traceback import print_exc + +PRETRAINED_MODELS = ROOT_PATH + '/' + PRETRAINED_MODELS_DIR + 'CARLA/' + +from tensorflow.python.framework.errors_impl import NotFoundError +from tensorflow.python.framework.errors_impl import UnimplementedError +import tensorflow as tf + +import os +os.environ['CUDA_VISIBLE_DEVICES'] = '-1' + +#gpus = tf.config.experimental.list_physical_devices('GPU') +#for gpu in gpus: +# tf.config.experimental.set_memory_growth(gpu, True) + + + +class Brain: + + def __init__(self, sensors, actuators, handler, model, config=None): + self.camera_0 = sensors.get_camera('camera_0') + self.camera_1 = sensors.get_camera('camera_1') + self.camera_2 = sensors.get_camera('camera_2') + self.camera_3 = sensors.get_camera('camera_3') + + self.cameras_first_images = [] + + self.pose = sensors.get_pose3d('pose3d_0') + + self.bird_eye_view = sensors.get_bird_eye_view('bird_eye_view_0') + + self.motors = actuators.get_motor('motors_0') + self.handler = handler + self.config = config + self.inference_times = [] + self.gpu_inference = True if tf.test.gpu_device_name() else False + + self.threshold_image = np.zeros((640, 360, 3), np.uint8) + self.color_image = np.zeros((640, 360, 3), np.uint8) + + client = carla.Client('localhost', 2000) + client.set_timeout(10.0) # seconds + world = client.get_world() + + time.sleep(5) + self.vehicle = world.get_actors().filter('vehicle.*')[0] + + if model: + if not path.exists(PRETRAINED_MODELS + model): + logger.info("File " + model + " cannot be found in " + PRETRAINED_MODELS) + logger.info("** Load TF model **") + self.net = tf.keras.models.load_model(PRETRAINED_MODELS + model) + logger.info("** Loaded TF model **") + else: + logger.info("** Brain not loaded **") + logger.info("- Models path: " + PRETRAINED_MODELS) + logger.info("- Model: " + str(model)) + + self.image_1 = 0 + self.image_2 = 0 + self.image_3 = 0 + self.image_4 = 0 + self.image_5 = 0 + self.image_6 = 0 + self.image_7 = 0 + self.image_8 = 0 + self.image_9 = 0 + self.image_10 = 0 + + self.image_11 = 0 + self.image_12 = 0 + self.image_13 = 0 + self.image_14 = 0 + self.image_15 = 0 + self.image_16 = 0 + self.image_17 = 0 + self.image_18 = 0 + self.image_19 = 0 + self.image_20 = 0 + + self.bird_eye_view_images = 0 + self.bird_eye_view_unique_images = 0 + + + def update_frame(self, frame_id, data): + """Update the information to be shown in one of the GUI's frames. + + Arguments: + frame_id {str} -- Id of the frame that will represent the data + data {*} -- Data to be shown in the frame. Depending on the type of frame (rgbimage, laser, pose3d, etc) + """ + if data.shape[0] != data.shape[1]: + if data.shape[0] > data.shape[1]: + difference = data.shape[0] - data.shape[1] + extra_left, extra_right = int(difference/2), int(difference/2) + extra_top, extra_bottom = 0, 0 + else: + difference = data.shape[1] - data.shape[0] + extra_left, extra_right = 0, 0 + extra_top, extra_bottom = int(difference/2), int(difference/2) + + + data = np.pad(data, ((extra_top, extra_bottom), (extra_left, extra_right), (0, 0)), mode='constant', constant_values=0) + + self.handler.update_frame(frame_id, data) + + def update_pose(self, pose_data): + self.handler.update_pose3d(pose_data) + + def execute(self): + image = self.camera_0.getImage().data + image_1 = self.camera_1.getImage().data + image_2 = self.camera_2.getImage().data + image_3 = self.camera_3.getImage().data + + bird_eye_view_1 = self.bird_eye_view.getImage(self.vehicle) + bird_eye_view_1 = cv2.cvtColor(bird_eye_view_1, cv2.COLOR_BGR2RGB) + + if self.cameras_first_images == []: + self.cameras_first_images.append(image) + self.cameras_first_images.append(image_1) + self.cameras_first_images.append(image_2) + self.cameras_first_images.append(image_3) + self.cameras_first_images.append(bird_eye_view_1) + + self.cameras_last_images = [ + image, + image_1, + image_2, + image_3, + bird_eye_view_1 + ] + + self.update_frame('frame_1', image_1) + self.update_frame('frame_2', image_2) + self.update_frame('frame_3', image_3) + + self.update_frame('frame_0', bird_eye_view_1) + + self.update_pose(self.pose.getPose3d()) + + image_shape=(50, 150) + img_base = cv2.resize(bird_eye_view_1, image_shape) + + AUGMENTATIONS_TEST = Compose([ + Normalize() + ]) + image = AUGMENTATIONS_TEST(image=img_base) + img = image["image"] + + if type(self.image_1) is int: + self.image_1 = img + elif type(self.image_2) is int: + self.image_2 = img + elif type(self.image_3) is int: + self.image_3 = img + elif type(self.image_4) is int: + self.image_4 = img + elif type(self.image_5) is int: + self.image_5 = img + elif type(self.image_6) is int: + self.image_6 = img + elif type(self.image_7) is int: + self.image_7 = img + elif type(self.image_8) is int: + self.image_8 = img + elif type(self.image_9) is int: + self.image_9 = img + + elif type(self.image_10) is int: + self.image_10 = img + elif type(self.image_11) is int: + self.image_11 = img + elif type(self.image_12) is int: + self.image_12 = img + elif type(self.image_13) is int: + self.image_13 = img + elif type(self.image_14) is int: + self.image_14 = img + elif type(self.image_15) is int: + self.image_15 = img + elif type(self.image_16) is int: + self.image_16 = img + elif type(self.image_17) is int: + self.image_17 = img + elif type(self.image_18) is int: + self.image_18 = img + elif type(self.image_19) is int: + self.image_19 = img + elif type(self.image_20) is int: + self.image_20 = img + else: + self.bird_eye_view_images += 1 + if (self.image_20==img).all() == False: + self.bird_eye_view_unique_images += 1 + self.image_1 = self.image_2 + self.image_2 = self.image_3 + self.image_3 = self.image_4 + self.image_4 = self.image_5 + self.image_5 = self.image_6 + self.image_6 = self.image_7 + self.image_7 = self.image_8 + self.image_8 = self.image_9 + self.image_9 = self.image_10 + + self.image_10 = self.image_11 + self.image_11 = self.image_12 + self.image_12 = self.image_13 + self.image_13 = self.image_14 + self.image_14 = self.image_15 + self.image_15 = self.image_16 + self.image_16 = self.image_17 + self.image_17 = self.image_18 + self.image_18 = self.image_19 + + self.image_19 = self.image_20 + self.image_20 = img + + img = [self.image_1, self.image_5, self.image_10, self.image_15, self.image_20] + img = np.expand_dims(img, axis=0) + + start_time = time.time() + try: + prediction = self.net.predict(img, verbose=0) + self.inference_times.append(time.time() - start_time) + throttle = prediction[0][0] + steer = prediction[0][1] * (1 - (-1)) + (-1) + break_command = prediction[0][2] + speed = self.vehicle.get_velocity() + vehicle_speed = 3.6 * math.sqrt(speed.x**2 + speed.y**2 + speed.z**2) + + if vehicle_speed > 30: + self.motors.sendThrottle(0.0) + self.motors.sendSteer(steer) + self.motors.sendBrake(break_command) + else: + if vehicle_speed < 5: + self.motors.sendThrottle(1.0) + self.motors.sendSteer(0.0) + self.motors.sendBrake(0) + else: + self.motors.sendThrottle(0.75) + self.motors.sendSteer(steer) + self.motors.sendBrake(break_command) + + except NotFoundError as ex: + logger.info('Error inside brain: NotFoundError!') + logger.warning(type(ex).__name__) + print_exc() + raise Exception(ex) + except UnimplementedError as ex: + logger.info('Error inside brain: UnimplementedError!') + logger.warning(type(ex).__name__) + print_exc() + raise Exception(ex) + except Exception as ex: + logger.info('Error inside brain: Exception!') + logger.warning(type(ex).__name__) + print_exc() + raise Exception(ex) \ No newline at end of file diff --git a/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_x9_V_MAX_30.py b/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_x9_V_MAX_30.py new file mode 100644 index 00000000..418c8ddd --- /dev/null +++ b/behavior_metrics/brains/CARLA/tensorflow/brain_carla_bird_eye_deep_learning_x9_V_MAX_30.py @@ -0,0 +1,359 @@ +#!/usr/bin/python +# -*- coding: utf-8 -*- +import csv +import cv2 +import math +import numpy as np +import threading +import time +import carla +from os import path +from albumentations import ( + Compose, Normalize, RandomRain, RandomBrightness, RandomShadow, RandomSnow, RandomFog, RandomSunFlare +) +from utils.constants import PRETRAINED_MODELS_DIR, ROOT_PATH +from utils.logger import logger +from traceback import print_exc + +PRETRAINED_MODELS = ROOT_PATH + '/' + PRETRAINED_MODELS_DIR + 'CARLA/' + +from tensorflow.python.framework.errors_impl import NotFoundError +from tensorflow.python.framework.errors_impl import UnimplementedError +import tensorflow as tf + +import os +os.environ['CUDA_VISIBLE_DEVICES'] = '-1' + +#gpus = tf.config.experimental.list_physical_devices('GPU') +#for gpu in gpus: +# tf.config.experimental.set_memory_growth(gpu, True) + + + +class Brain: + + def __init__(self, sensors, actuators, handler, model, config=None): + self.camera_0 = sensors.get_camera('camera_0') + self.camera_1 = sensors.get_camera('camera_1') + self.camera_2 = sensors.get_camera('camera_2') + self.camera_3 = sensors.get_camera('camera_3') + + self.cameras_first_images = [] + + self.pose = sensors.get_pose3d('pose3d_0') + + self.bird_eye_view = sensors.get_bird_eye_view('bird_eye_view_0') + + self.motors = actuators.get_motor('motors_0') + self.handler = handler + self.config = config + self.inference_times = [] + self.gpu_inference = True if tf.test.gpu_device_name() else False + + self.threshold_image = np.zeros((640, 360, 3), np.uint8) + self.color_image = np.zeros((640, 360, 3), np.uint8) + + client = carla.Client('localhost', 2000) + client.set_timeout(10.0) # seconds + world = client.get_world() + + time.sleep(5) + self.vehicle = world.get_actors().filter('vehicle.*')[0] + + if model: + if not path.exists(PRETRAINED_MODELS + model): + logger.info("File " + model + " cannot be found in " + PRETRAINED_MODELS) + logger.info("** Load TF model **") + self.net = tf.keras.models.load_model(PRETRAINED_MODELS + model) + logger.info("** Loaded TF model **") + else: + logger.info("** Brain not loaded **") + logger.info("- Models path: " + PRETRAINED_MODELS) + logger.info("- Model: " + str(model)) + + self.image_1 = 0 + self.image_2 = 0 + self.image_3 = 0 + self.image_4 = 0 + self.image_5 = 0 + self.image_6 = 0 + self.image_7 = 0 + self.image_8 = 0 + self.image_9 = 0 + self.image_10 = 0 + + self.image_11 = 0 + self.image_12 = 0 + self.image_13 = 0 + self.image_14 = 0 + self.image_15 = 0 + self.image_16 = 0 + self.image_17 = 0 + self.image_18 = 0 + self.image_19 = 0 + self.image_20 = 0 + + self.image_21 = 0 + self.image_22 = 0 + self.image_23 = 0 + self.image_24 = 0 + self.image_25 = 0 + self.image_26 = 0 + self.image_27 = 0 + self.image_28 = 0 + self.image_29 = 0 + self.image_30 = 0 + + self.image_31 = 0 + self.image_32 = 0 + self.image_33 = 0 + self.image_34 = 0 + self.image_35 = 0 + self.image_36 = 0 + self.image_37 = 0 + self.image_38 = 0 + self.image_39 = 0 + self.image_40 = 0 + + self.bird_eye_view_images = 0 + self.bird_eye_view_unique_images = 0 + + + def update_frame(self, frame_id, data): + """Update the information to be shown in one of the GUI's frames. + + Arguments: + frame_id {str} -- Id of the frame that will represent the data + data {*} -- Data to be shown in the frame. Depending on the type of frame (rgbimage, laser, pose3d, etc) + """ + if data.shape[0] != data.shape[1]: + if data.shape[0] > data.shape[1]: + difference = data.shape[0] - data.shape[1] + extra_left, extra_right = int(difference/2), int(difference/2) + extra_top, extra_bottom = 0, 0 + else: + difference = data.shape[1] - data.shape[0] + extra_left, extra_right = 0, 0 + extra_top, extra_bottom = int(difference/2), int(difference/2) + + + data = np.pad(data, ((extra_top, extra_bottom), (extra_left, extra_right), (0, 0)), mode='constant', constant_values=0) + + self.handler.update_frame(frame_id, data) + + def update_pose(self, pose_data): + self.handler.update_pose3d(pose_data) + + def execute(self): + image = self.camera_0.getImage().data + image_1 = self.camera_1.getImage().data + image_2 = self.camera_2.getImage().data + image_3 = self.camera_3.getImage().data + + bird_eye_view_1 = self.bird_eye_view.getImage(self.vehicle) + bird_eye_view_1 = cv2.cvtColor(bird_eye_view_1, cv2.COLOR_BGR2RGB) + + if self.cameras_first_images == []: + self.cameras_first_images.append(image) + self.cameras_first_images.append(image_1) + self.cameras_first_images.append(image_2) + self.cameras_first_images.append(image_3) + self.cameras_first_images.append(bird_eye_view_1) + + self.cameras_last_images = [ + image, + image_1, + image_2, + image_3, + bird_eye_view_1 + ] + + self.update_frame('frame_1', image_1) + self.update_frame('frame_2', image_2) + self.update_frame('frame_3', image_3) + + self.update_frame('frame_0', bird_eye_view_1) + + self.update_pose(self.pose.getPose3d()) + + image_shape=(50, 150) + img_base = cv2.resize(bird_eye_view_1, image_shape) + + AUGMENTATIONS_TEST = Compose([ + Normalize() + ]) + image = AUGMENTATIONS_TEST(image=img_base) + img = image["image"] + + if type(self.image_1) is int: + self.image_1 = img + elif type(self.image_2) is int: + self.image_2 = img + elif type(self.image_3) is int: + self.image_3 = img + elif type(self.image_4) is int: + self.image_4 = img + elif type(self.image_5) is int: + self.image_5 = img + elif type(self.image_6) is int: + self.image_6 = img + elif type(self.image_7) is int: + self.image_7 = img + elif type(self.image_8) is int: + self.image_8 = img + elif type(self.image_9) is int: + self.image_9 = img + + elif type(self.image_10) is int: + self.image_10 = img + elif type(self.image_11) is int: + self.image_11 = img + elif type(self.image_12) is int: + self.image_12 = img + elif type(self.image_13) is int: + self.image_13 = img + elif type(self.image_14) is int: + self.image_14 = img + elif type(self.image_15) is int: + self.image_15 = img + elif type(self.image_16) is int: + self.image_16 = img + elif type(self.image_17) is int: + self.image_17 = img + elif type(self.image_18) is int: + self.image_18 = img + elif type(self.image_19) is int: + self.image_19 = img + elif type(self.image_20) is int: + self.image_20 = img + elif type(self.image_21) is int: + self.image_21 = img + elif type(self.image_22) is int: + self.image_22 = img + elif type(self.image_23) is int: + self.image_23 = img + elif type(self.image_24) is int: + self.image_24 = img + elif type(self.image_25) is int: + self.image_25 = img + elif type(self.image_26) is int: + self.image_26 = img + elif type(self.image_27) is int: + self.image_27 = img + elif type(self.image_28) is int: + self.image_28 = img + elif type(self.image_29) is int: + self.image_29 = img + elif type(self.image_30) is int: + self.image_30 = img + elif type(self.image_31) is int: + self.image_31 = img + elif type(self.image_32) is int: + self.image_32 = img + elif type(self.image_33) is int: + self.image_33 = img + elif type(self.image_34) is int: + self.image_34 = img + elif type(self.image_35) is int: + self.image_35 = img + elif type(self.image_36) is int: + self.image_36 = img + elif type(self.image_37) is int: + self.image_37 = img + elif type(self.image_38) is int: + self.image_38 = img + elif type(self.image_39) is int: + self.image_39 = img + elif type(self.image_40) is int: + self.image_40 = img + else: + self.bird_eye_view_images += 1 + if (self.image_40==img).all() == False: + self.bird_eye_view_unique_images += 1 + self.image_1 = self.image_2 + self.image_2 = self.image_3 + self.image_3 = self.image_4 + self.image_4 = self.image_5 + self.image_5 = self.image_6 + self.image_6 = self.image_7 + self.image_7 = self.image_8 + self.image_8 = self.image_9 + self.image_9 = self.image_10 + + self.image_10 = self.image_11 + self.image_11 = self.image_12 + self.image_12 = self.image_13 + self.image_13 = self.image_14 + self.image_14 = self.image_15 + self.image_15 = self.image_16 + self.image_16 = self.image_17 + self.image_17 = self.image_18 + self.image_18 = self.image_19 + + self.image_19 = self.image_20 + self.image_20 = self.image_21 + self.image_21 = self.image_22 + self.image_22 = self.image_23 + self.image_23 = self.image_24 + self.image_24 = self.image_25 + self.image_25 = self.image_26 + self.image_26 = self.image_27 + self.image_27 = self.image_28 + + self.image_28 = self.image_29 + self.image_29 = self.image_30 + self.image_30 = self.image_31 + self.image_31 = self.image_32 + self.image_32 = self.image_33 + self.image_33 = self.image_34 + self.image_34 = self.image_35 + self.image_35 = self.image_36 + self.image_36 = self.image_37 + + self.image_37 = self.image_38 + self.image_38 = self.image_39 + self.image_39 = self.image_40 + self.image_40 = img + + img = [self.image_1, self.image_5, self.image_10, self.image_15, self.image_20, self.image_25, self.image_30, self.image_35, self.image_40] + img = np.expand_dims(img, axis=0) + + start_time = time.time() + try: + prediction = self.net.predict(img, verbose=0) + self.inference_times.append(time.time() - start_time) + throttle = prediction[0][0] + steer = prediction[0][1] * (1 - (-1)) + (-1) + break_command = prediction[0][2] + speed = self.vehicle.get_velocity() + vehicle_speed = 3.6 * math.sqrt(speed.x**2 + speed.y**2 + speed.z**2) + + if vehicle_speed > 30: + self.motors.sendThrottle(0.0) + self.motors.sendSteer(steer) + self.motors.sendBrake(break_command) + else: + if vehicle_speed < 5: + self.motors.sendThrottle(1.0) + self.motors.sendSteer(0.0) + self.motors.sendBrake(0) + else: + self.motors.sendThrottle(0.75) + self.motors.sendSteer(steer) + self.motors.sendBrake(break_command) + + except NotFoundError as ex: + logger.info('Error inside brain: NotFoundError!') + logger.warning(type(ex).__name__) + print_exc() + raise Exception(ex) + except UnimplementedError as ex: + logger.info('Error inside brain: UnimplementedError!') + logger.warning(type(ex).__name__) + print_exc() + raise Exception(ex) + except Exception as ex: + logger.info('Error inside brain: Exception!') + logger.warning(type(ex).__name__) + print_exc() + raise Exception(ex) \ No newline at end of file diff --git a/behavior_metrics/brains/gazebo/__init__.py b/behavior_metrics/brains/gazebo/__init__.py new file mode 100644 index 00000000..e69de29b diff --git a/behavior_metrics/brains/gazebo/f1/brain_f1_follow_line_ddpg.py b/behavior_metrics/brains/gazebo/f1/brain_f1_follow_line_ddpg.py new file mode 100644 index 00000000..94f9c0a1 --- /dev/null +++ b/behavior_metrics/brains/gazebo/f1/brain_f1_follow_line_ddpg.py @@ -0,0 +1,264 @@ + +import tensorflow as tf +from gym.envs.registration import register +from brains.gazebo.f1.rl_utils.inference import InferencerWrapper +import yaml +import gym +import numpy as np +import time + +# F1 envs +if 'F1Env-v0' not in gym.envs.registry.env_specs: + gym.envs.register( + id='F1Env-v0', + entry_point='brains.gazebo.f1.rl_utils.models:F1Env', + # More arguments here + ) +else: + print("Environment F1Env-v0 is already registered.") + + + + +class LoadEnvVariablesDDPGGazebo: + """ + ONLY FOR DDPG algorithm + Creates a new variable 'environment', which contains values to Gazebo env, Carla env ... + """ + + def __init__(self, config) -> None: + """environment variable for reset(), step() methods""" + self.environment_set = config["settings"]["environment_set"] + self.env = config["settings"]["env"] + self.agent = config["settings"]["agent"] + self.states = config["settings"]["states"] + self.actions = config["settings"]["actions"] + self.actions_set = config["actions"][self.actions] + self.rewards = config["settings"]["rewards"] + ##### environment variable + self.environment = {} + self.environment["agent"] = config["settings"]["agent"] + self.environment["algorithm"] = config["settings"]["algorithm"] + self.environment["task"] = config["settings"]["task"] + self.environment["framework"] = config["settings"]["framework"] + self.environment["model_state_name"] = config[self.environment_set][self.env][ + "model_state_name" + ] + # Training/inference + self.environment["mode"] = config["settings"]["mode"] + self.environment["retrain_ddpg_tf_actor_model_name"] = config["retraining"][ + "ddpg" + ]["retrain_ddpg_tf_actor_model_name"] + self.environment["retrain_ddpg_tf_critic_model_name"] = config["retraining"][ + "ddpg" + ]["retrain_ddpg_tf_critic_model_name"] + self.environment["inference_ddpg_tf_actor_model_name"] = config["inference"][ + "ddpg" + ]["inference_ddpg_tf_actor_model_name"] + self.environment["inference_ddpg_tf_critic_model_name"] = config["inference"][ + "ddpg" + ]["inference_ddpg_tf_critic_model_name"] + + # Env + self.environment["env"] = config["settings"]["env"] + self.environment["circuit_name"] = config[self.environment_set][self.env][ + "circuit_name" + ] + self.environment["launchfile"] = config[self.environment_set][self.env][ + "launchfile" + ] + self.environment["environment_folder"] = config[self.environment_set][self.env][ + "environment_folder" + ] + self.environment["robot_name"] = config[self.environment_set][self.env][ + "robot_name" + ] + self.environment["estimated_steps"] = config[self.environment_set][self.env][ + "estimated_steps" + ] + self.environment["alternate_pose"] = config[self.environment_set][self.env][ + "alternate_pose" + ] + self.environment["sensor"] = config[self.environment_set][self.env]["sensor"] + self.environment["gazebo_start_pose"] = [ + config[self.environment_set][self.env]["circuit_positions_set"][0] + ] + self.environment["gazebo_random_start_pose"] = config[self.environment_set][ + self.env + ]["circuit_positions_set"] + self.environment["telemetry_mask"] = config[self.environment_set][self.env][ + "telemetry_mask" + ] + self.environment["telemetry"] = config[self.environment_set][self.env][ + "telemetry" + ] + + # Image + self.environment["height_image"] = config["agent"][self.agent][ + "camera_params" + ]["height"] + self.environment["width_image"] = config["agent"][self.agent]["camera_params"][ + "width" + ] + self.environment["center_image"] = config["agent"][self.agent][ + "camera_params" + ]["center_image"] + self.environment["image_resizing"] = config["agent"][self.agent][ + "camera_params" + ]["image_resizing"] + self.environment["new_image_size"] = config["agent"][self.agent][ + "camera_params" + ]["new_image_size"] + self.environment["raw_image"] = config["agent"][self.agent]["camera_params"][ + "raw_image" + ] + self.environment["num_regions"] = config["agent"][self.agent]["camera_params"][ + "num_regions" + ] + self.environment["lower_limit"] = config["agent"][self.agent]["camera_params"][ + "lower_limit" + ] + # States + self.environment["states"] = config["settings"]["states"] + self.environment["x_row"] = config["states"][self.states][0] + + # Actions + self.environment["action_space"] = config["settings"]["actions"] + self.environment["actions"] = config["actions"][self.actions] + + # Rewards + self.environment["reward_function"] = config["settings"]["rewards"] + self.environment["rewards"] = config["rewards"][self.rewards] + self.environment["min_reward"] = config["rewards"][self.rewards]["min_reward"] + + # Algorithm + self.environment["critic_lr"] = config["algorithm"]["ddpg"]["critic_lr"] + self.environment["actor_lr"] = config["algorithm"]["ddpg"]["actor_lr"] + self.environment["model_name"] = config["algorithm"]["ddpg"]["model_name"] + # + self.environment["ROS_MASTER_URI"] = config["ros"]["ros_master_uri"] + self.environment["GAZEBO_MASTER_URI"] = config["ros"]["gazebo_master_uri"] + + +# Sharing GPU +gpus = tf.config.experimental.list_physical_devices("GPU") +for gpu in gpus: + tf.config.experimental.set_memory_growth(gpu, True) + + +from pydantic import BaseModel +class InferenceExecutorValidator(BaseModel): + settings: dict + agent: dict + environment: dict + algorithm: dict + inference: dict + # gazebo: dict + + +class Brain: + def __init__(self, sensors, actuators, handler, config=None): + self.camera = sensors.get_camera('camera_0') + self.motors = actuators.get_motor('motors_0') + self.handler = handler + self.config = config + self.suddenness_distance = [0] + self.st = 0 + self.en = 0 + + args = { + 'algorithm': 'ddpg', + 'environment': 'simple', + 'agent': 'f1', + 'filename': 'brains/gazebo/f1/config/config_inference_followline_ddpg_f1_gazebo.yaml' + } + + f = open(args['filename'], "r") + read_file = f.read() + + config_file = yaml.load(read_file, Loader=yaml.FullLoader) + + inference_params = { + "settings": self.get_settings(config_file), + "algorithm": self.get_algorithm(config_file, args['algorithm']), + "inference": self.get_inference(config_file, args['algorithm']), + "environment": self.get_environment(config_file, args['environment']), + "agent": self.get_agent(config_file, args['agent']), + } + + params = InferenceExecutorValidator(**inference_params) + + self.env_name = params.environment["params"]["env_name"] + env_params = params.environment["params"] + actions = params.environment["actions"] + env_params["actions"] = actions + self.environment = LoadEnvVariablesDDPGGazebo(config_file) + + self.env = gym.make(self.env_name, **self.environment.environment) + + self.inference_file = params.inference["params"]["inference_ddpg_tf_actor_model_name"] + observation, _ = self.env.reset() + + self.step = 1 + self.state = observation + + self.inferencer = InferencerWrapper("ddpg", self.inference_file, env=config_file) + + def get_algorithm(self, config_file: dict, input_algorithm: str) -> dict: + return { + "name": input_algorithm, + "params": config_file["algorithm"][input_algorithm], + } + + + def get_environment(self, config_file: dict, input_env: str) -> dict: + return { + "name": input_env, + "params": config_file["environments"][input_env], + "actions": config_file["actions"], + } + + + def get_agent(self, config_file: dict, input_agent: str) -> dict: + return { + "name": input_agent, + "params": config_file["agent"][input_agent], + } + + + def get_inference(self, config_file: dict, input_inference: str) -> dict: + return { + "name": input_inference, + "params": config_file["inference"][input_inference], + } + + + def get_settings(self, config_file: dict) -> dict: + return { + "name": "settings", + "params": config_file["settings"], + } + + def update_frame(self, frame_id, data): + """Update the information to be shown in one of the GUI's frames. + + Arguments: + frame_id {str} -- Id of the frame that will represent the data + data {*} -- Data to be shown in the frame. Depending on the type of frame (rgbimage, laser, pose3d, etc) + """ + + self.handler.update_frame(frame_id, data) + + + def execute(self): + action = self.inferencer.inference(self.state) + + observation, reward, done, info = self.env.step(action, self.step) + + self.step += 1 + self.state = observation + + image = self.camera.getImage().data + + self.update_frame('frame_0', image) + diff --git a/behavior_metrics/brains/gazebo/f1/brain_f1_follow_line_dqn.py b/behavior_metrics/brains/gazebo/f1/brain_f1_follow_line_dqn.py index 8c026bf3..c68c10ba 100644 --- a/behavior_metrics/brains/gazebo/f1/brain_f1_follow_line_dqn.py +++ b/behavior_metrics/brains/gazebo/f1/brain_f1_follow_line_dqn.py @@ -183,7 +183,7 @@ def __init__(self, sensors, actuators, handler, config=None): self.inference_file = params.inference["params"]["inference_file"] observation = self.env.reset() self.step = 1 - self.state = "".join(map(str, observation)) + self.state = observation[0] self.inferencer = InferencerWrapper("dqn", self.inference_file, env=config_file) @@ -238,9 +238,7 @@ def execute(self): # Execute the action and get feedback observation, reward, done, info = self.env.step(action, self.step) self.step += 1 - - self.state = "".join(map(str, observation)) - + self.state = observation image = self.camera.getImage().data self.update_frame('frame_0', image) diff --git a/behavior_metrics/brains/gazebo/f1/brain_f1_follow_line_ppo.py b/behavior_metrics/brains/gazebo/f1/brain_f1_follow_line_ppo.py new file mode 100644 index 00000000..0a6b6282 --- /dev/null +++ b/behavior_metrics/brains/gazebo/f1/brain_f1_follow_line_ppo.py @@ -0,0 +1,263 @@ + +import tensorflow as tf +from gym.envs.registration import register +from brains.gazebo.f1.rl_utils.inference import InferencerWrapper +import yaml +import gym +import numpy as np +import time + +# F1 envs +if 'F1Env-v0' not in gym.envs.registry.env_specs: + gym.envs.register( + id='F1Env-v0', + entry_point='brains.gazebo.f1.rl_utils.models:F1Env', + # More arguments here + ) +else: + print("Environment F1Env-v0 is already registered.") + + + + +class LoadEnvVariablesPPOGazebo: + """ + ONLY FOR ppo algorithm + Creates a new variable 'environment', which contains values to Gazebo env, Carla env ... + """ + + def __init__(self, config) -> None: + """environment variable for reset(), step() methods""" + self.environment_set = config["settings"]["environment_set"] + self.env = config["settings"]["env"] + self.agent = config["settings"]["agent"] + self.states = config["settings"]["states"] + self.actions = config["settings"]["actions"] + self.actions_set = config["actions"][self.actions] + self.rewards = config["settings"]["rewards"] + ##### environment variable + self.environment = {} + self.environment["agent"] = config["settings"]["agent"] + self.environment["algorithm"] = config["settings"]["algorithm"] + self.environment["task"] = config["settings"]["task"] + self.environment["framework"] = config["settings"]["framework"] + self.environment["model_state_name"] = config[self.environment_set][self.env][ + "model_state_name" + ] + # Training/inference + self.environment["mode"] = config["settings"]["mode"] + + self.environment["inference_ppo_tf_model_name"] = config["inference"][ + "ppo" + ]["inference_ppo_tf_model_name"] + + # Env + self.environment["env"] = config["settings"]["env"] + self.environment["circuit_name"] = config[self.environment_set][self.env][ + "circuit_name" + ] + self.environment["launchfile"] = config[self.environment_set][self.env][ + "launchfile" + ] + self.environment["environment_folder"] = config[self.environment_set][self.env][ + "environment_folder" + ] + self.environment["robot_name"] = config[self.environment_set][self.env][ + "robot_name" + ] + self.environment["estimated_steps"] = config[self.environment_set][self.env][ + "estimated_steps" + ] + self.environment["alternate_pose"] = config[self.environment_set][self.env][ + "alternate_pose" + ] + self.environment["sensor"] = config[self.environment_set][self.env]["sensor"] + self.environment["gazebo_start_pose"] = [ + config[self.environment_set][self.env]["circuit_positions_set"][0] + ] + self.environment["gazebo_random_start_pose"] = config[self.environment_set][ + self.env + ]["circuit_positions_set"] + self.environment["telemetry_mask"] = config[self.environment_set][self.env][ + "telemetry_mask" + ] + self.environment["telemetry"] = config[self.environment_set][self.env][ + "telemetry" + ] + + # Image + self.environment["height_image"] = config["agent"][self.agent][ + "camera_params" + ]["height"] + self.environment["width_image"] = config["agent"][self.agent]["camera_params"][ + "width" + ] + self.environment["center_image"] = config["agent"][self.agent][ + "camera_params" + ]["center_image"] + self.environment["image_resizing"] = config["agent"][self.agent][ + "camera_params" + ]["image_resizing"] + self.environment["new_image_size"] = config["agent"][self.agent][ + "camera_params" + ]["new_image_size"] + self.environment["raw_image"] = config["agent"][self.agent]["camera_params"][ + "raw_image" + ] + self.environment["num_regions"] = config["agent"][self.agent]["camera_params"][ + "num_regions" + ] + self.environment["lower_limit"] = config["agent"][self.agent]["camera_params"][ + "lower_limit" + ] + # States + self.environment["states"] = config["settings"]["states"] + self.environment["x_row"] = config["states"][self.states][0] + + # Actions + self.environment["action_space"] = config["settings"]["actions"] + self.environment["actions"] = config["actions"][self.actions] + + # Rewards + self.environment["reward_function"] = config["settings"]["rewards"] + self.environment["rewards"] = config["rewards"][self.rewards] + self.environment["min_reward"] = config["rewards"][self.rewards]["min_reward"] + + # Algorithm + self.environment["critic_lr"] = config["algorithm"]["ppo"]["critic_lr"] + self.environment["actor_lr"] = config["algorithm"]["ppo"]["actor_lr"] + self.environment["model_name"] = config["algorithm"]["ppo"]["model_name"] + # + self.environment["ROS_MASTER_URI"] = config["ros"]["ros_master_uri"] + self.environment["GAZEBO_MASTER_URI"] = config["ros"]["gazebo_master_uri"] + + +# Sharing GPU +gpus = tf.config.experimental.list_physical_devices("GPU") +for gpu in gpus: + tf.config.experimental.set_memory_growth(gpu, True) + + +from pydantic import BaseModel +class InferenceExecutorValidator(BaseModel): + settings: dict + agent: dict + environment: dict + algorithm: dict + inference: dict + # gazebo: dict + + +class Brain: + def __init__(self, sensors, actuators, handler, config=None): + self.camera = sensors.get_camera('camera_0') + self.motors = actuators.get_motor('motors_0') + self.handler = handler + self.config = config + self.suddenness_distance = [0] + self.st = 0 + self.en = 0 + + args = { + 'algorithm': 'ppo', + 'environment': 'simple', + 'agent': 'f1', + 'filename': 'brains/gazebo/f1/config/config_inference_followline_ppo_f1_gazebo.yaml' + } + + f = open(args['filename'], "r") + read_file = f.read() + + config_file = yaml.load(read_file, Loader=yaml.FullLoader) + + inference_params = { + "settings": self.get_settings(config_file), + "algorithm": self.get_algorithm(config_file, args['algorithm']), + "inference": self.get_inference(config_file, args['algorithm']), + "environment": self.get_environment(config_file, args['environment']), + "agent": self.get_agent(config_file, args['agent']), + } + + params = InferenceExecutorValidator(**inference_params) + + self.env_name = params.environment["params"]["env_name"] + env_params = params.environment["params"] + actions = params.environment["actions"] + env_params["actions"] = actions + self.environment = LoadEnvVariablesPPOGazebo(config_file) + + self.env = gym.make(self.env_name, **self.environment.environment) + + self.inference_file = params.inference["params"]["inference_ppo_tf_model_name"] + observation, _ = self.env.reset() + + self.step = 1 + self.state = observation + + self.inferencer = InferencerWrapper("ppo", self.inference_file, env=config_file) + + def get_algorithm(self, config_file: dict, input_algorithm: str) -> dict: + return { + "name": input_algorithm, + "params": config_file["algorithm"][input_algorithm], + } + + + def get_environment(self, config_file: dict, input_env: str) -> dict: + return { + "name": input_env, + "params": config_file["gazebo_environments"][input_env], + "actions": config_file["actions"], + } + + + def get_agent(self, config_file: dict, input_agent: str) -> dict: + return { + "name": input_agent, + "params": config_file["agent"][input_agent], + } + + + def get_inference(self, config_file: dict, input_inference: str) -> dict: + return { + "name": input_inference, + "params": config_file["inference"][input_inference], + } + + + def get_settings(self, config_file: dict) -> dict: + return { + "name": "settings", + "params": config_file["settings"], + } + + def update_frame(self, frame_id, data): + """Update the information to be shown in one of the GUI's frames. + + Arguments: + frame_id {str} -- Id of the frame that will represent the data + data {*} -- Data to be shown in the frame. Depending on the type of frame (rgbimage, laser, pose3d, etc) + """ + + self.handler.update_frame(frame_id, data) + + + def execute(self): + action = self.inferencer.inference(self.state) + action[0] = (action[0] + 1) * 4 # TODO scale it propperly + action[1] = action[1] * 1.5 + observation, reward, done, info = self.env.step(action, self.step) + # print(f"{action}") + # self.st_prev=self.st + # self.st=time.time() + # print(f"debug: time lapsed between last iteration {self.st_prev-self.st}") + + + self.step += 1 + + self.state = observation + + image = self.camera.getImage().data + + self.update_frame('frame_0', image) + diff --git a/behavior_metrics/brains/gazebo/f1/brain_f1_follow_line_qlearn.py b/behavior_metrics/brains/gazebo/f1/brain_f1_follow_line_qlearn.py index b29471ff..1135e48a 100644 --- a/behavior_metrics/brains/gazebo/f1/brain_f1_follow_line_qlearn.py +++ b/behavior_metrics/brains/gazebo/f1/brain_f1_follow_line_qlearn.py @@ -44,7 +44,7 @@ def __init__(self, sensors, actuators, handler, config=None): 'algorithm': 'qlearn', 'environment': 'simple', 'agent': 'f1', - 'filename': 'brains/gazebo/sf1/config/config_f1_qlearn.yaml' + 'filename': 'brains/gazebo/f1/config/config_f1_qlearn.yaml' } f = open(args['filename'], "r") diff --git a/behavior_metrics/brains/gazebo/f1/config/config_f1_qlearn.yaml b/behavior_metrics/brains/gazebo/f1/config/config_f1_qlearn.yaml index d5e06329..8e76144b 100644 --- a/behavior_metrics/brains/gazebo/f1/config/config_f1_qlearn.yaml +++ b/behavior_metrics/brains/gazebo/f1/config/config_f1_qlearn.yaml @@ -22,7 +22,7 @@ actions: actions_set: simple #simple available_actions: simple: - 0: [ 3, 0 ] + 0: [ 6, 0 ] 1: [ 2, 1 ] 2: [ 2, -1 ] diff --git a/behavior_metrics/brains/gazebo/f1/config/config_inference_followline_ddpg_f1_gazebo.yaml b/behavior_metrics/brains/gazebo/f1/config/config_inference_followline_ddpg_f1_gazebo.yaml new file mode 100644 index 00000000..b8e278f4 --- /dev/null +++ b/behavior_metrics/brains/gazebo/f1/config/config_inference_followline_ddpg_f1_gazebo.yaml @@ -0,0 +1,140 @@ +settings: + mode: inference # training, retraining, inference + task: ddpg_follow_line # follow_line_gazebo, follow_lane_gazebo, autoparking_gazebo + algorithm: ddpg # qlearn, dqn, ddpg, ppo + simulator: gazebo # openai, carla, gazebo, sumo + environment_set: environments # gazebo_environments, carla_environments + env: simple # simple, nurburgring, montreal, curves, simple_laser, manual, autoparking + agent: f1 # f1, autoparkingRL, auto_carla, mountain_car, robot_mesh, cartpole, turtlebot + actions: continuous # continuous, simple, medium, hard, test, autoparking_simple + states: sp10 #image, sp1 (simplified perception with 1 point), sp3 (simplified perception with 3 points), spn (simplified perception with n points) + rewards: followline_center # followline_center, followline_center_v_w_linear + framework: TensorFlow # TensorFlow, Pytorch + total_episodes: 500000 + training_time: 72 + models_dir: "./checkpoints" + logs_dir: "./logs" + metrics_dir: "./metrics" + debug_stats: false + show_monitoring: True + +ros: + ros_master_uri: "11311" + gazebo_master_uri: "11345" + +retraining: + ddpg: + retrain_ddpg_tf_actor_model_name: + retrain_ddpg_tf_critic_model_name: + +inference: + ddpg: + inference_ddpg_tf_actor_model_name: "/home/ruben/Desktop/my-BehaviorMetrics/behavior_metrics/models/gazebo/rl_models/ddpg/superfast-20231118-220658_IMPROVED_C-simple_S-sp5_A-continuous_MR-2025_E-3797/ACTOR" + inference_ddpg_tf_critic_model_name: "/home/ruben/Desktop/my-BehaviorMetrics/behavior_metrics/models/gazebo/rl_models/ddpg/superfast-20231118-220658_IMPROVED_C-simple_S-sp5_A-continuous_MR-2025_E-3797/CRITIC" + +algorithm: + ddpg: + gamma: 0.9 + tau: 0.01 + std_dev: 0 + model_name: DDPG_Actor_conv2d32x64_Critic_conv2d32x64 + replay_memory_size: 50_000 + memory_fraction: 0.20 + critic_lr: 0.003 + actor_lr: 0.002 + buffer_capacity: 100_000 + batch_size: 128 + +agent: + f1: + camera_params: + width: 640 + height: 480 + center_image: 320 + raw_image: False + image_resizing: 100 + new_image_size: 32 + num_regions: 16 + lower_limit: 220 + +states: + image: + 0: [3] + sp1: + 0: [40] #TODO + sp3: + 0: [10, 50, 150] + sp5: + 0: [20, 50, 77, 130, 200] + sp10: + 0: [10, 40, 70, 100, 130, 160, 190, 220] + spn: + 0: [10] + +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] + continuous: + v: [1, 10] + w: [-1.5, 1.5] + +rewards: + followline_center: + from_10: 10 + from_02: 2 + from_01: 1 + penal: -100 + min_reward: 5_000 + highest_reward: 100 + followline_center_v_w_linear: # only for continuous actions + beta_0: 3 + beta_1: -0.1 + penal: 0 + min_reward: 1_000 + highest_reward: 100 + +environments: + simple: + env_name: F1Env-v0 + circuit_name: simple + launchfile: simple_circuit.launch + environment_folder: f1 + robot_name: f1_renault + model_state_name: f1_renault # f1_renault_multicamera_multilaser + start_pose: 0 # 0, 1, 2, 3, 4 + alternate_pose: False + estimated_steps: 5000 + sensor: camera + save_episodes: 1 + save_every_step: 20000 + lap_completed: False + save_model: True + save_positions: True + debug_level: DEBUG + telemetry: False + telemetry_mask: False + plotter_graphic: False + circuit_positions_set: + 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] #finish line + 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] diff --git a/behavior_metrics/brains/gazebo/f1/config/config_inference_followline_dqn_f1_gazebo.yaml b/behavior_metrics/brains/gazebo/f1/config/config_inference_followline_dqn_f1_gazebo.yaml index 1f189826..97c52e08 100644 --- a/behavior_metrics/brains/gazebo/f1/config/config_inference_followline_dqn_f1_gazebo.yaml +++ b/behavior_metrics/brains/gazebo/f1/config/config_inference_followline_dqn_f1_gazebo.yaml @@ -6,8 +6,8 @@ settings: environment_set: environments # gazebo_environments, carla_environments env: simple # simple, nurburgring, montreal, curves, simple_laser, manual, autoparking agent: f1 # f1, autoparkingRL, auto_carla, mountain_car, robot_mesh, cartpole, turtlebot - actions: simple # simple, medium, hard, test - states: sp1 #image, sp1 (simplified perception with 1 point), sp3 (simplified perception with 3 points), spn (simplified perception with n points) + actions: hard # simple, medium, hard, test + states: sp10 #image, sp1 (simplified perception with 1 point), sp3 (simplified perception with 3 points), spn (simplified perception with n points) rewards: followline_center # rewards_followline_center framework: TensorFlow # TensorFlow, Pytorch total_episodes: 5 @@ -26,13 +26,13 @@ retraining: inference: dqn: - inference_file: models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max5334_Epoch596_inTime20230310-223500.model + inference_file: /home/ruben/Desktop/my-BehaviorMetrics/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max2951_Epoch267_inTime20231220-121204.model algorithm: dqn: alpha: 0.8 gamma: 0.9 - epsilon: 0.99 + epsilon: 0.000001 epsilon_discount: 0.9986 epsilon_min: 0.05 model_name: DQN_sp_16x16 @@ -64,29 +64,33 @@ states: sp3: 0: [5, 15, 22] sp5: - 0: [3, 5, 10, 15, 20] + 0: [13, 25, 60, 110, 160] + sp10: + 0: [3, 15, 30, 45, 50, 70, 100, 120, 150, 190] spn: 0: [10] actions: simple: - 0: [3, 0] - 1: [2, 1] - 2: [2, -1] + 0: [5, 0] + 1: [0.5, 0.2] + 2: [0.5, -0.2] medium: - 0: [3, 0] - 1: [2, 1] - 2: [2, -1] - 3: [1, 1.5] - 4: [1, -1.5] + 0: [ 1, 0 ] + 1: [ 1, 1 ] + 2: [ 1, -1 ] + 3: [ 1, 0.5 ] + 4: [ 1, -0.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] + 0: [7, 0] + 1: [4, 1,5] + 2: [4, -1,5] + 3: [3, 1] + 4: [3, -1] + 5: [2, 1] + 6: [2, -1] + 7: [1, 0.5] + 8: [1, -0.5] test: 0: [0, 0] diff --git a/behavior_metrics/brains/gazebo/f1/config/config_inference_followline_ppo_f1_gazebo.yaml b/behavior_metrics/brains/gazebo/f1/config/config_inference_followline_ppo_f1_gazebo.yaml new file mode 100644 index 00000000..c212e342 --- /dev/null +++ b/behavior_metrics/brains/gazebo/f1/config/config_inference_followline_ppo_f1_gazebo.yaml @@ -0,0 +1,144 @@ +settings: + mode: inference # training, retraining, inference + task: ppo_follow_line # follow_line_gazebo, follow_lane_gazebo, autoparking_gazebo + algorithm: ppo_continuous # qlearn, dqn, ddpg, ppo + simulator: gazebo # openai, carla, gazebo, sumo + environment_set: gazebo_environments # gazebo_environments, carla_environments + env: simple # simple, nurburgring, montreal, curves, simple_laser, manual, autoparking + agent: f1 # f1, autoparkingRL, auto_carla, mountain_car, robot_mesh, cartpole, turtlebot + actions: continuous # continuous, simple, medium, hard, test, autoparking_simple + states: sp5 #image, sp1 (simplified perception with 1 point), sp3 (simplified perception with 3 points), spn (simplified perception with n points) + rewards: followline_center # followline_center, followline_center_v_w_linear + framework: TensorFlow # TensorFlow, Pytorch + total_episodes: 500000 + training_time: 72 + models_dir: "./checkpoints" + recorder_carla_dir: + logs_dir: "./logs" + metrics_dir: "./metrics" + debug_stats: false + show_monitoring: true + steps_to_decrease: 30000 + decrease_substraction: 0.01 + decrease_min: 0.03 + reward_params: + function: pow + punish_zig_zag_value: 1 + punish_ineffective_vel: 0 + beta_1: 0.5 + +ros: + ros_master_uri: "11311" + gazebo_master_uri: "11345" + +retraining: + ppo: + retrain_ppo_tf_model_name: "/home/ruben/Desktop/my-BehaviorMetrics/behavior_metrics/models/gazebo/rl_models/ppo/20231118-232134_LAPCOMPLETEDMaxReward-1084_Epoch-3" +inference: + ppo: + inference_ppo_tf_model_name: /home/ruben/Desktop/RL-Studio/rl_studio/checkpoints/follow_line_gazebo_ppo_continuous_f1_TensorFlow/20231113-193415_LAPCOMPLETEDMaxReward-2788_Epoch-69 + +algorithm: + ppo: + gamma: 0.9 + epsilon: 0.15 + std_dev: 0.0001 + episodes_update: 1_000 + replay_memory_size: 50_000 + memory_fraction: 0.20 + critic_lr: 0.002 + actor_lr: 0.001 + model_name: PPO_Actor_conv2d32x64_Critic_conv2d32x64 + +agent: + f1: + camera_params: + width: 640 + height: 480 + center_image: 320 + raw_image: False + image_resizing: 100 + new_image_size: 32 + num_regions: 16 + lower_limit: 220 + +states: + image: + 0: [3] + sp1: + 0: [40] #TODO + sp3: + 0: [10, 50, 150] + sp5: + 0: [10, 40, 70, 100, 130, 160, 190, 220] + sp10: + 0: [3, 15, 30, 45, 50, 70, 100, 120, 150, 190] + spn: + 0: [10] + +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] + continuous: + v: [1, 7] + w: [-1.5, 1.5] + +rewards: + followline_center: + from_10: 10 + from_02: 2 + from_01: 1 + penal: -100 + min_reward: 5_000 + highest_reward: 100 + followline_center_v_w_linear: # only for continuous actions + penal: 0 + min_reward: 1_000 + highest_reward: 100 + +gazebo_environments: + simple: + env_name: F1Env-v0 + circuit_name: simple + launchfile: simple_circuit.launch + environment_folder: f1 + robot_name: f1_renault + model_state_name: f1_renault # f1_renault_multicamera_multilaser + start_pose: 0 # 0, 1, 2, 3, 4 + alternate_pose: True + estimated_steps: 5000 + sensor: camera + save_episodes: 1 + save_every_step: 20000 + lap_completed: False + save_model: True + save_positions: True + debug_level: DEBUG + telemetry: False + telemetry_mask: False + plotter_graphic: False + circuit_positions_set: + 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] #finish line + 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] + sleep: 0.055 diff --git a/behavior_metrics/brains/gazebo/f1/rl_utils/__init__.py b/behavior_metrics/brains/gazebo/f1/rl_utils/__init__.py new file mode 100644 index 00000000..e69de29b diff --git a/behavior_metrics/brains/gazebo/f1/rl_utils/algorithms/__init__.py b/behavior_metrics/brains/gazebo/f1/rl_utils/algorithms/__init__.py index f43387af..6e82069e 100644 --- a/behavior_metrics/brains/gazebo/f1/rl_utils/algorithms/__init__.py +++ b/behavior_metrics/brains/gazebo/f1/rl_utils/algorithms/__init__.py @@ -1,6 +1,8 @@ from brains.gazebo.f1.rl_utils.algorithms.algorithms_type import AlgorithmsType from brains.gazebo.f1.rl_utils.algorithms.qlearn_f1 import QLearnF1 from brains.gazebo.f1.rl_utils.algorithms.dqn_f1 import DQNF1 +from brains.gazebo.f1.rl_utils.algorithms.ddpg_f1 import DDPGF1 +from brains.gazebo.f1.rl_utils.algorithms.ppo_f1 import PPOF1 class InferencerFactory: def __new__(cls, config): @@ -22,3 +24,19 @@ def __new__(cls, config): return brain + if algorithm == AlgorithmsType.DDPG.value: + brain = DDPGF1(config.env) + brain.load_inference_model(inference_file_name) + + return brain + + if algorithm == AlgorithmsType.PPO.value: + brain = PPOF1(8, 2, 0, + 0, 0, 0, 0, True, 0.00001) + + # Init Agents + brain.load(inference_file_name) + + return brain + + diff --git a/behavior_metrics/brains/gazebo/f1/rl_utils/algorithms/algorithms_type.py b/behavior_metrics/brains/gazebo/f1/rl_utils/algorithms/algorithms_type.py index e59f0d26..b3e191d5 100644 --- a/behavior_metrics/brains/gazebo/f1/rl_utils/algorithms/algorithms_type.py +++ b/behavior_metrics/brains/gazebo/f1/rl_utils/algorithms/algorithms_type.py @@ -6,4 +6,5 @@ class AlgorithmsType(Enum): QLEARN_MULTIPLE_STATES = "qlearn_multiple_states" DQN = "dqn" DDPG = "ddpg" + PPO = "ppo" MANUAL = "manual" diff --git a/behavior_metrics/brains/gazebo/f1/rl_utils/algorithms/ddpg_f1.py b/behavior_metrics/brains/gazebo/f1/rl_utils/algorithms/ddpg_f1.py new file mode 100644 index 00000000..ef9d12d6 --- /dev/null +++ b/behavior_metrics/brains/gazebo/f1/rl_utils/algorithms/ddpg_f1.py @@ -0,0 +1,35 @@ +import numpy as np +import tensorflow as tf + +from keras.models import Sequential, load_model + +from .loaders import ( + LoadGlobalParams, +) + +# Sharing GPU +gpus = tf.config.experimental.list_physical_devices("GPU") +for gpu in gpus: + tf.config.experimental.set_memory_growth(gpu, True) + +class DDPGF1: + def __init__(self, config=None): + self.global_params = LoadGlobalParams(config) + self.state_space = self.global_params.states + + pass + + def load_inference_model(self, models_dir): + """ """ + path_inference_model = models_dir + inference_model = load_model(path_inference_model, compile=False) + self.model = inference_model + + return self + + def inference(self, state): + tf_prev_state = tf.expand_dims(tf.convert_to_tensor(state), 0) + sampled_actions = tf.squeeze(self.model(tf_prev_state)) + sampled_actions = sampled_actions.numpy() + # sampled_actions = np.argmax(sampled_actions) + return np.squeeze(sampled_actions) diff --git a/behavior_metrics/brains/gazebo/f1/rl_utils/algorithms/dqn_f1.py b/behavior_metrics/brains/gazebo/f1/rl_utils/algorithms/dqn_f1.py index ef4e8780..2b2243b0 100644 --- a/behavior_metrics/brains/gazebo/f1/rl_utils/algorithms/dqn_f1.py +++ b/behavior_metrics/brains/gazebo/f1/rl_utils/algorithms/dqn_f1.py @@ -34,5 +34,4 @@ def inference(self, state): 0 ] else: - return self.model.predict([int(state)], verbose=0)[0] - + return self.model(np.array([state]))[0] diff --git a/behavior_metrics/brains/gazebo/f1/rl_utils/algorithms/ppo_f1.py b/behavior_metrics/brains/gazebo/f1/rl_utils/algorithms/ppo_f1.py new file mode 100644 index 00000000..a403e827 --- /dev/null +++ b/behavior_metrics/brains/gazebo/f1/rl_utils/algorithms/ppo_f1.py @@ -0,0 +1,175 @@ +import torch +import torch.nn as nn +from torch.distributions import MultivariateNormal +from torch.distributions import Categorical +import numpy as np + +################################## set device ################################## +print("============================================================================================") +# set device to cpu or cuda +device = torch.device('cpu') +if (torch.cuda.is_available()): + device = torch.device('cuda:0') + torch.cuda.empty_cache() + print("Device set to : " + str(torch.cuda.get_device_name(device))) +else: + print("Device set to : cpu") +print("============================================================================================") + + +################################## PPO Policy ################################## +class RolloutBuffer: + def __init__(self): + self.actions = [] + self.states = [] + self.logprobs = [] + self.rewards = [] + self.is_terminals = [] + + def clear(self): + del self.actions[:] + del self.states[:] + del self.logprobs[:] + del self.rewards[:] + del self.is_terminals[:] + + +class ActorCritic(nn.Module): + def __init__(self, state_dim, action_dim, has_continuous_action_space, action_std_init): + super(ActorCritic, self).__init__() + action_std_init = 0.0001 if action_std_init is None else action_std_init + + self.has_continuous_action_space = has_continuous_action_space + + if has_continuous_action_space: + self.action_dim = action_dim + self.action_var = torch.full((action_dim,), action_std_init * action_std_init).to(device) + # actor + if has_continuous_action_space: + self.actor = nn.Sequential( + nn.Linear(state_dim, 64), + nn.Tanh(), + nn.Linear(64, 64), + nn.Tanh(), + nn.Linear(64, action_dim), + nn.Tanh(), + ) + else: + self.actor = nn.Sequential( + nn.Linear(state_dim, 64), + nn.Tanh(), + nn.Linear(64, 64), + nn.Tanh(), + nn.Linear(64, action_dim), + nn.Softmax(dim=-1) + ) + # critic + self.critic = nn.Sequential( + nn.Linear(state_dim, 64), + nn.Tanh(), + nn.Linear(64, 64), + nn.Tanh(), + nn.Linear(64, 1) + ) + + def set_action_std(self, new_action_std): + if self.has_continuous_action_space: + self.action_var = torch.full((self.action_dim,), new_action_std * new_action_std).to(device) + else: + print("--------------------------------------------------------------------------------------------") + print("WARNING : Calling ActorCritic::set_action_std() on discrete action space policy") + print("--------------------------------------------------------------------------------------------") + + def forward(self): + raise NotImplementedError + + def act(self, state): + if self.has_continuous_action_space: + action_mean = self.actor(state) + cov_mat = torch.diag(self.action_var).unsqueeze(dim=0) + dist = MultivariateNormal(action_mean.float(), cov_mat.float()) + else: + action_probs = self.actor(state) + dist = Categorical(action_probs) + + action = dist.sample() + action_logprob = dist.log_prob(action) + + return action.detach(), action_logprob.detach() + + def evaluate(self, state, action): + + if self.has_continuous_action_space: + action_mean = self.actor(state) + + action_var = self.action_var.expand_as(action_mean) + cov_mat = torch.diag_embed(action_var).to(device) + dist = MultivariateNormal(action_mean, cov_mat) + + # For Single Action Environments. + if self.action_dim == 1: + action = action.reshape(-1, self.action_dim) + else: + action_probs = self.actor(state) + dist = Categorical(action_probs) + action_logprobs = dist.log_prob(action) + dist_entropy = dist.entropy() + state_values = self.critic(state) + + return action_logprobs, state_values, dist_entropy + + +class PPOF1: + def __init__(self, state_dim, action_dim, lr_actor=0.0003, lr_critic=0.001, gamma=None, K_epochs=80, eps_clip=None, + has_continuous_action_space=True, action_std_init=0.2): + self.action_std_decay_rate = 0.05 # linearly decay action_std (action_std = action_std - action_std_decay_rate) + self.min_action_std = 0.1 # minimum action_std (stop decay after action_std <= min_action_std) + self.action_std_decay_freq = int(2.5e5) # action_std decay frequency (in num timesteps) + self.has_continuous_action_space = has_continuous_action_space + + if has_continuous_action_space: + self.action_std = action_std_init + + self.gamma = gamma + self.eps_clip = eps_clip + self.K_epochs = K_epochs + + self.buffer = RolloutBuffer() + self.policy_old = ActorCritic(state_dim, action_dim, has_continuous_action_space, action_std_init).to(device) + self.optimizer = torch.optim.Adam([ + {'params': self.policy_old.actor.parameters(), 'lr': lr_actor}, + {'params': self.policy_old.critic.parameters(), 'lr': lr_critic} + ]) + + self.MseLoss = nn.MSELoss() + + def select_action(self, state): + + if self.has_continuous_action_space: + with torch.no_grad(): + # state = torch.FloatTensor(state).to(device) + state = torch.tensor(state).to(device) + action, action_logprob = self.policy_old.act(state) + + self.buffer.states.append(state) + self.buffer.actions.append(action) + self.buffer.logprobs.append(action_logprob) + + return action.detach().cpu().numpy().flatten() + else: + + with torch.no_grad(): + state = torch.FloatTensor(state).to(device) + action, action_logprob = self.policy_old.act(state) + + self.buffer.states.append(state) + self.buffer.actions.append(action) + self.buffer.logprobs.append(action_logprob) + + return action.item() + + def inference(self, state): + return self.select_action(state) + + def load(self, checkpoint_path): + self.policy_old.load_state_dict(torch.load(checkpoint_path, map_location=lambda storage, loc: storage)) diff --git a/behavior_metrics/brains/gazebo/f1/rl_utils/env_type.py b/behavior_metrics/brains/gazebo/f1/rl_utils/env_type.py index 26abec92..89f6525e 100644 --- a/behavior_metrics/brains/gazebo/f1/rl_utils/env_type.py +++ b/behavior_metrics/brains/gazebo/f1/rl_utils/env_type.py @@ -10,3 +10,5 @@ class EnvironmentType(Enum): manual_env = "manual" ddpg_env_follow_line = "ddpg_follow_line" ddpg_env_follow_lane = "ddpg_follow_lane" + ppo_env_follow_line = "ppo_follow_line" + diff --git a/behavior_metrics/brains/gazebo/f1/rl_utils/models/__init__.py b/behavior_metrics/brains/gazebo/f1/rl_utils/models/__init__.py index 38e16346..4ed561f6 100644 --- a/behavior_metrics/brains/gazebo/f1/rl_utils/models/__init__.py +++ b/behavior_metrics/brains/gazebo/f1/rl_utils/models/__init__.py @@ -2,17 +2,20 @@ from brains.gazebo.f1.rl_utils.exceptions import NoValidEnvironmentType from brains.gazebo.f1.rl_utils.models.f1_env_camera import QlearnF1FollowLineEnvGazebo from brains.gazebo.f1.rl_utils.models.followline_dqn_tf import FollowLineDQNF1GazeboTF - +from brains.gazebo.f1.rl_utils.models.followline_ddpg_tf import FollowLineDDPGF1GazeboTF class F1Env: def __new__(cls, **config): task = config.get("task") - # Qlearn F1 FollowLine camera if task == EnvironmentType.qlearn_env_camera_follow_line.value: return QlearnF1FollowLineEnvGazebo(**config) elif task == EnvironmentType.dqn_env_follow_line.value: return FollowLineDQNF1GazeboTF(**config) + elif task == EnvironmentType.ddpg_env_follow_line.value: + return FollowLineDDPGF1GazeboTF(**config) + elif task == EnvironmentType.ppo_env_follow_line.value: + return FollowLineDDPGF1GazeboTF(**config) else: raise NoValidEnvironmentType(task) diff --git a/behavior_metrics/brains/gazebo/f1/rl_utils/models/followline_ddpg_tf.py b/behavior_metrics/brains/gazebo/f1/rl_utils/models/followline_ddpg_tf.py new file mode 100644 index 00000000..d49f821b --- /dev/null +++ b/behavior_metrics/brains/gazebo/f1/rl_utils/models/followline_ddpg_tf.py @@ -0,0 +1,54 @@ +############################################# +# - Task: Follow Line +# - Algorithm: DQN +# - actions: discrete +# - State: Simplified perception and raw image +# +############################################ + +from geometry_msgs.msg import Twist +import numpy as np + +from brains.gazebo.f1.rl_utils.models.f1_env import F1Env +from .settings import F1GazeboTFConfig + + +class FollowLineDDPGF1GazeboTF(F1Env): + def __init__(self, **config): + + ###### init F1env + F1Env.__init__(self, **config) + ###### init class variables + F1GazeboTFConfig.__init__(self, **config) + + def reset(self): + from .reset import ( + Reset, + ) + + if self.state_space == "image": + return Reset.reset_f1_state_image(self) + else: + return Reset.reset_f1_state_sp(self) + + def step(self, action, step): + from .step import ( + StepFollowLine, + ) + + if self.state_space == "image" and self.action_space != "continuous": + return StepFollowLine.step_followline_state_image_actions_discretes( + self, action, step + ) + elif self.state_space == "image" and self.action_space == "continuous": + return StepFollowLine.step_followline_state_image_actions_continuous( + self, action, step + ) + elif self.state_space != "image" and self.action_space == "continuous": + return StepFollowLine.step_followline_state_sp_actions_continuous( + self, action, step + ) + else: + return StepFollowLine.step_followline_state_sp_actions_discretes( + self, action, step + ) diff --git a/behavior_metrics/brains/gazebo/f1/rl_utils/models/reset.py b/behavior_metrics/brains/gazebo/f1/rl_utils/models/reset.py index d286e015..df0d949b 100644 --- a/behavior_metrics/brains/gazebo/f1/rl_utils/models/reset.py +++ b/behavior_metrics/brains/gazebo/f1/rl_utils/models/reset.py @@ -51,25 +51,16 @@ def reset_f1_state_sp(self): # self._gazebo_set_fix_pose_f1_follow_right_lane() self._gazebo_reset() - self._gazebo_unpause() ##==== get image from sensor camera f1_image_camera, _ = self.f1gazeboimages.get_camera_info() - self._gazebo_pause() ##==== calculating State # simplified perception as observation - centrals_in_pixels, _ = self.simplifiedperception.calculate_centrals_lane( - f1_image_camera.data, - self.height, - self.width, - self.x_row, - self.lower_limit, - self.center_image, - ) - states = self.simplifiedperception.calculate_observation( - centrals_in_pixels, self.center_image, self.pixel_region + points_in_red_line, centrals_normalized = self.simplifiedperception.processed_image( + f1_image_camera.data, self.height, self.width, self.x_row, self.center_image ) - state = [states[0]] + states = centrals_normalized + state_size = len(states) - return state + return states, state_size diff --git a/behavior_metrics/brains/gazebo/f1/rl_utils/models/step.py b/behavior_metrics/brains/gazebo/f1/rl_utils/models/step.py index 94902bf2..b96e7c56 100644 --- a/behavior_metrics/brains/gazebo/f1/rl_utils/models/step.py +++ b/behavior_metrics/brains/gazebo/f1/rl_utils/models/step.py @@ -1,6 +1,5 @@ from geometry_msgs.msg import Twist import numpy as np -import time from brains.gazebo.f1.rl_utils.models.f1_env import F1Env @@ -29,7 +28,6 @@ def step_followline_state_image_actions_discretes(self, action, step): self.point = points_in_red_line[0] center = abs(float(self.center_image - self.point) / (float(self.width) // 2)) - # center = float(self.center_image - self.point) / (float(self.width) // 2) ##==== get State ##==== image as observation @@ -57,7 +55,7 @@ def step_followline_state_sp_actions_discretes(self, action, step): f1_image_camera, _ = self.f1gazeboimages.get_camera_info() ##==== get center - points_in_red_line, _ = self.simplifiedperception.processed_image( + points_in_red_line, centrals_normalized = self.simplifiedperception.processed_image( f1_image_camera.data, self.height, self.width, self.x_row, self.center_image ) if self.state_space == "spn": @@ -70,17 +68,17 @@ def step_followline_state_sp_actions_discretes(self, action, step): ##==== get State ##==== simplified perception as observation - state = self.simplifiedperception.calculate_observation( - points_in_red_line, self.center_image, self.pixel_region - ) + # state = self.simplifiedperception.calculate_observation( + # points_in_red_line, self.center_image, self.pixel_region + # ) ##==== get Rewards - if self.reward_function == "followline_center": - reward, done = self.f1gazeborewards.rewards_followline_center( - center, self.rewards - ) + # if self.reward_function == "followline_center": + # reward, done = self.f1gazeborewards.rewards_followline_center( + # center, self.rewards + # ) - return state, reward, done, {} + return centrals_normalized, 0, False, {} def step_followline_state_image_actions_continuous(self, action, step): self._gazebo_unpause() @@ -103,7 +101,6 @@ def step_followline_state_image_actions_continuous(self, action, step): self.point = points_in_red_line[0] center = abs(float(self.center_image - self.point) / (float(self.width) // 2)) - # center = float(self.center_image - self.point) / (float(self.width) // 2) ##==== get State state = np.array( @@ -125,18 +122,20 @@ def step_followline_state_image_actions_continuous(self, action, step): return state, reward, done, {} def step_followline_state_sp_actions_continuous(self, action, step): - self._gazebo_unpause() vel_cmd = Twist() - vel_cmd.linear.x = action[0][0] - vel_cmd.angular.z = action[0][1] - self.vel_pub.publish(vel_cmd) + vel_cmd.linear.x = action[0] + vel_cmd.angular.z = action[1] + self.vel_pub.publish(vel_cmd) ##==== get image from sensor camera f1_image_camera, _ = self.f1gazeboimages.get_camera_info() - self._gazebo_pause() + + self.previous_image = f1_image_camera + while np.array_equal(self.previous_image, f1_image_camera.data): + f1_image_camera, _ = self.f1gazeboimages.get_camera_info() ##==== get center - points_in_red_line, _ = self.simplifiedperception.processed_image( + points_in_red_line, centrals_normalized = self.simplifiedperception.processed_image( f1_image_camera.data, self.height, self.width, self.x_row, self.center_image ) if self.state_space == "spn": @@ -144,26 +143,13 @@ def step_followline_state_sp_actions_continuous(self, action, step): else: self.point = points_in_red_line[0] - center = abs(float(self.center_image - self.point) / (float(self.width) // 2)) - # center = float(self.center_image - self.point) / (float(self.width) // 2) - ##==== get State ##==== simplified perception as observation - state = self.simplifiedperception.calculate_observation( - points_in_red_line, self.center_image, self.pixel_region - ) - - ##==== get Rewards - if self.reward_function == "followline_center": - reward, done = self.f1gazeborewards.rewards_followline_center( - center, self.rewards - ) - else: - reward, done = self.f1gazeborewards.rewards_followline_v_w_centerline( - vel_cmd, center, self.rewards, self.beta_1, self.beta_0 - ) + # state = self.simplifiedperception.calculate_observation( + # points_in_red_line, self.center_image, self.pixel_region + # ) - return state, reward, done, {} + return centrals_normalized, 0, False, None class StepFollowLane(F1Env): @@ -190,35 +176,13 @@ def step_followlane_state_sp_actions_discretes(self, action, step): else: self.point = centrals_in_lane[0] - # center = abs(float(self.center_image - self.point) / (float(self.width) // 2)) - #center = float(self.center_image - self.point) / (float(self.width) // 2) - - #print(f"\n{centrals_in_lane = }") - #print(f"\n{centrals_in_lane_normalized = }") - #print(f"\n{self.point = }") - #print(f"\n{center = }") - ##==== get State ##==== simplified perception as observation state = self.simplifiedperception.calculate_observation( centrals_in_lane, self.center_image, self.pixel_region ) - ##==== get Rewards - if self.reward_function == "follow_right_lane_center_v_step": - reward, done = self.f1gazeborewards.rewards_followlane_v_centerline_step( - vel_cmd, centrals_in_lane_normalized[0], step, self.rewards - ) - else: - reward, done = self.f1gazeborewards.rewards_followlane_centerline( - centrals_in_lane_normalized[0], self.rewards - ) - - return state, reward, done, {} - - - - + return state, 0, False, {} def step_followlane_state_image_actions_discretes(self, action, step): self._gazebo_unpause() diff --git a/behavior_metrics/configs/gazebo/DL-torch-lstm.yml b/behavior_metrics/configs/gazebo/DL-torch-lstm.yml index 38c12de0..bfd341d5 100644 --- a/behavior_metrics/configs/gazebo/DL-torch-lstm.yml +++ b/behavior_metrics/configs/gazebo/DL-torch-lstm.yml @@ -16,7 +16,7 @@ Behaviors: Topic: '/F1ROS/cmd_vel' MaxV: 3 MaxW: 0.3 - BrainPath: 'brains/gazebo/ssf1/brain_f1_torch-lstm.py' + BrainPath: 'brains/gazebo/f1/brain_f1_torch-lstm.py' PilotTimeCycle: 50 Parameters: Model: 'model_lstm_pilotnet_torch.ckpt' diff --git a/behavior_metrics/configs/gazebo/default-multiple.yml b/behavior_metrics/configs/gazebo/default-multiple.yml index d8facdb9..04f52681 100644 --- a/behavior_metrics/configs/gazebo/default-multiple.yml +++ b/behavior_metrics/configs/gazebo/default-multiple.yml @@ -16,22 +16,23 @@ Behaviors: Topic: '/F1ROS/cmd_vel' MaxV: 3 MaxW: 0.3 - BrainPath: ['brains/gazebo/f1/brain_f1_follow_line_dqn.py', 'brains/gazebo/f1/brain_f1_follow_line_qlearn.py'] + BrainPath: ['brains/gazebo/f1/brain_f1_follow_line_ppo.py', 'brains/gazebo/f1/brain_f1_follow_line_dqn.py', 'brains/gazebo/f1/brain_f1_follow_line_qlearn.py', 'brains/gazebo/f1/brain_f1_follow_line_ddpg.py'] PilotTimeCycle: 50 Parameters: # Model: ['model_deepest_lstm_cropped_250_norm_max_pooling.h5', 'model_deepest_lstm_cropped_250_norm_test.h5'] ImageCropped: True - ImageSize: [100,50] + ImageSize: [100, 50] ImageNormalized: True PredictionsNormalized: True GPU: True + Environment: gazebo Type: 'f1' Experiment: Name: "Experiment name" Description: "Experiment description" - Timeout: [5, 5] - UseWorldTimeouts: [5, 5] - Repetitions: 5 + Timeout: [300, 500] + UseWorldTimeouts: [50, 50] + Repetitions: 3 Simulation: World: ['/opt/jderobot/share/jderobot/gazebo/launch/simple_circuit.launch', '/opt/jderobot/share/jderobot/gazebo/launch/many_curves.launch'] RealTimeUpdateRate: 1000 diff --git a/behavior_metrics/configs/gazebo/default-rl-ddpg.yml b/behavior_metrics/configs/gazebo/default-rl-ddpg.yml new file mode 100644 index 00000000..7ec79c64 --- /dev/null +++ b/behavior_metrics/configs/gazebo/default-rl-ddpg.yml @@ -0,0 +1,50 @@ +Behaviors: + Robot: + Sensors: + Cameras: + Camera_0: + Name: 'camera_0' + Topic: '/F1ROS/cameraL/image_raw' + Pose3D: + Pose3D_0: + Name: 'pose3d_0' + Topic: '/F1ROS/odom' + Actuators: + Motors: + Motors_0: + Name: 'motors_0' + Topic: '/F1ROS/cmd_vel' + MaxV: 3 + MaxW: 0.3 + + BrainPath: 'brains/gazebo/f1/brain_f1_follow_line_ddpg.py' + PilotTimeCycle: 50 + Parameters: + ImageTranform: '' + Environment: 'gazebo' + Type: 'f1' + Simulation: + World: /usr/local/gazebo/launch/simple_circuit.launch + Dataset: + In: '/tmp/my_bag.bag' + Out: '' + Stats: + Out: './' + PerfectLap: './perfect_bags/lap-simple-circuit.bag' + Layout: + Frame_0: + Name: frame_0 + Geometry: [1, 1, 2, 2] + Data: rgbimage + Frame_1: + Name: frame_1 + Geometry: [0, 1, 1, 1] + Data: rgbimage + Frame_2: + Name: frame_2 + Geometry: [0, 2, 1, 1] + Data: rgbimage + Frame_3: + Name: frame_3 + Geometry: [0, 3, 3, 1] + Data: rgbimage diff --git a/behavior_metrics/configs/gazebo/default-rl-dqn.yml b/behavior_metrics/configs/gazebo/default-rl-dqn.yml index 60e51aa4..58362f96 100644 --- a/behavior_metrics/configs/gazebo/default-rl-dqn.yml +++ b/behavior_metrics/configs/gazebo/default-rl-dqn.yml @@ -21,6 +21,7 @@ Behaviors: PilotTimeCycle: 50 Parameters: ImageTranform: '' + Environment: gazebo Type: 'f1' Simulation: World: /usr/local/gazebo/launch/simple_circuit.launch diff --git a/behavior_metrics/configs/gazebo/default-rl-ppo.yml b/behavior_metrics/configs/gazebo/default-rl-ppo.yml new file mode 100644 index 00000000..28e4f13a --- /dev/null +++ b/behavior_metrics/configs/gazebo/default-rl-ppo.yml @@ -0,0 +1,50 @@ +Behaviors: + Robot: + Sensors: + Cameras: + Camera_0: + Name: 'camera_0' + Topic: '/F1ROS/cameraL/image_raw' + Pose3D: + Pose3D_0: + Name: 'pose3d_0' + Topic: '/F1ROS/odom' + Actuators: + Motors: + Motors_0: + Name: 'motors_0' + Topic: '/F1ROS/cmd_vel' + MaxV: 3 + MaxW: 0.3 + + BrainPath: 'brains/gazebo/f1/brain_f1_follow_line_ppo.py' + PilotTimeCycle: 50 + Parameters: + ImageTranform: '' + Environment: 'gazebo' + Type: 'f1' + Simulation: + World: /usr/local/gazebo/launch/simple_circuit.launch + Dataset: + In: '/tmp/my_bag.bag' + Out: '' + Stats: + Out: './' + PerfectLap: './perfect_bags/lap-simple-circuit.bag' + Layout: + Frame_0: + Name: frame_0 + Geometry: [1, 1, 2, 2] + Data: rgbimage + Frame_1: + Name: frame_1 + Geometry: [0, 1, 1, 1] + Data: rgbimage + Frame_2: + Name: frame_2 + Geometry: [0, 2, 1, 1] + Data: rgbimage + Frame_3: + Name: frame_3 + Geometry: [0, 3, 3, 1] + Data: rgbimage diff --git a/behavior_metrics/configs/gazebo/default-rl-qlearn.yml b/behavior_metrics/configs/gazebo/default-rl-qlearn.yml index 43c1f04e..b811bf85 100644 --- a/behavior_metrics/configs/gazebo/default-rl-qlearn.yml +++ b/behavior_metrics/configs/gazebo/default-rl-qlearn.yml @@ -21,6 +21,7 @@ Behaviors: PilotTimeCycle: 50 Parameters: ImageTranform: '' + Environment: gazebo Type: 'f1' Simulation: World: /usr/local/gazebo/launch/simple_circuit.launch diff --git a/behavior_metrics/configs/gazebo/default-rl.yml b/behavior_metrics/configs/gazebo/default-rl.yml index d9fdfb66..e2a95f03 100644 --- a/behavior_metrics/configs/gazebo/default-rl.yml +++ b/behavior_metrics/configs/gazebo/default-rl.yml @@ -17,7 +17,7 @@ Behaviors: MaxV: 3 MaxW: 0.3 RL: True - BrainPath: 'brains/f1rl/train.py' + BrainPath: 'brains/gazebo/f1rl/train.py' PilotTimeCycle: 50 Type: 'f1rl' Parameters: diff --git a/behavior_metrics/driver_carla.py b/behavior_metrics/driver_carla.py index 0f9c2ed7..699d9d49 100644 --- a/behavior_metrics/driver_carla.py +++ b/behavior_metrics/driver_carla.py @@ -127,7 +127,7 @@ def is_config_correct(app_configuration): return is_correct -def generate_agregated_experiments_metrics(experiments_starting_time, experiments_elapsed_times): +def generate_agregated_experiments_metrics(experiments_starting_time, experiments_elapsed_times, app_configuration): result = metrics_carla.get_aggregated_experiments_list(experiments_starting_time) experiments_starting_time_dt = datetime.fromtimestamp(experiments_starting_time) @@ -252,28 +252,33 @@ def generate_agregated_experiments_metrics(experiments_starting_time, experiment 'metric': 'suddenness_distance_speed_per_km', 'title': 'Suddenness distance speed per km per experiment' }, - { - 'metric': 'dangerous_distance_pct_km', - 'title': 'Percentage of dangerous distance per km' - }, - { - 'metric': 'close_distance_pct_km', - 'title': 'Percentage of close distance per km' - }, - { - 'metric': 'medium_distance_pct_km', - 'title': 'Percentage of medium distance per km' - }, - { - 'metric': 'great_distance_pct_km', - 'title': 'Percentage of great distance per km' - }, + { 'metric': 'completed_laps', 'title': 'Completed laps per experiment' }, ] + if app_configuration.task == 'follow_lane_traffic': + experiments_metrics_and_titles.append( + { + 'metric': 'dangerous_distance_pct_km', + 'title': 'Percentage of dangerous distance per km' + }, + { + 'metric': 'close_distance_pct_km', + 'title': 'Percentage of close distance per km' + }, + { + 'metric': 'medium_distance_pct_km', + 'title': 'Percentage of medium distance per km' + }, + { + 'metric': 'great_distance_pct_km', + 'title': 'Percentage of great distance per km' + }, + ) + metrics_carla.get_all_experiments_aggregated_metrics(result, experiments_starting_time_str, experiments_metrics_and_titles) metrics_carla.get_per_model_aggregated_metrics(result, experiments_starting_time_str, experiments_metrics_and_titles) metrics_carla.get_all_experiments_aggregated_metrics_boxplot(result, experiments_starting_time_str, experiments_metrics_and_titles) @@ -413,7 +418,7 @@ def main(): logger.info('Invalid task type. Try "follow_route", "follow_lane" or "follow_lane_traffic". Killing program...') sys.exit(-1) experiments_elapsed_times['total_experiments_elapsed_time'] = time.time() - experiments_starting_time - generate_agregated_experiments_metrics(experiments_starting_time, experiments_elapsed_times) + generate_agregated_experiments_metrics(experiments_starting_time, experiments_elapsed_times, app_configuration) if app_configuration.experiment_random_spawn_point == True or app_configuration.task == 'follow_route': if os.path.isfile('tmp_circuit.launch'): os.remove('tmp_circuit.launch') diff --git a/behavior_metrics/models/gazebo/rl_models/ddpg/20231104-003119_LAPCOMPLETEDCircuit-simple_States-sp5_Actions-continuous_BATCH_Rewards-followline_center_MaxReward-3096_Epoch-277/ACTOR/fingerprint.pb b/behavior_metrics/models/gazebo/rl_models/ddpg/20231104-003119_LAPCOMPLETEDCircuit-simple_States-sp5_Actions-continuous_BATCH_Rewards-followline_center_MaxReward-3096_Epoch-277/ACTOR/fingerprint.pb new file mode 100644 index 00000000..10fe746e Binary files /dev/null and b/behavior_metrics/models/gazebo/rl_models/ddpg/20231104-003119_LAPCOMPLETEDCircuit-simple_States-sp5_Actions-continuous_BATCH_Rewards-followline_center_MaxReward-3096_Epoch-277/ACTOR/fingerprint.pb differ diff --git a/behavior_metrics/models/gazebo/rl_models/ddpg/20231104-003119_LAPCOMPLETEDCircuit-simple_States-sp5_Actions-continuous_BATCH_Rewards-followline_center_MaxReward-3096_Epoch-277/ACTOR/keras_metadata.pb b/behavior_metrics/models/gazebo/rl_models/ddpg/20231104-003119_LAPCOMPLETEDCircuit-simple_States-sp5_Actions-continuous_BATCH_Rewards-followline_center_MaxReward-3096_Epoch-277/ACTOR/keras_metadata.pb new file mode 100644 index 00000000..1006f597 --- /dev/null +++ b/behavior_metrics/models/gazebo/rl_models/ddpg/20231104-003119_LAPCOMPLETEDCircuit-simple_States-sp5_Actions-continuous_BATCH_Rewards-followline_center_MaxReward-3096_Epoch-277/ACTOR/keras_metadata.pb @@ -0,0 +1,18 @@ + +broot"_tf_keras_network*b{"name": "continuous_two_actions", "trainable": true, "expects_training_arg": true, "dtype": "float32", "batch_input_shape": null, "must_restore_from_config": false, "preserve_input_structure_in_config": false, "autocast": false, "class_name": "Functional", "config": {"name": "continuous_two_actions", "layers": [{"class_name": "InputLayer", "config": {"batch_input_shape": {"class_name": "__tuple__", "items": [null, 8]}, "dtype": "float32", "sparse": false, "ragged": false, "name": "input_1"}, "name": "input_1", "inbound_nodes": []}, {"class_name": "Dense", "config": {"name": "dense", "trainable": true, "dtype": "float32", "units": 10, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}}, "bias_initializer": {"class_name": "Zeros", "config": {}}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense", "inbound_nodes": [[["input_1", 0, 0, {}]], [["input_1", 0, 0, {}]]]}, {"class_name": "Dense", "config": {"name": "dense_1", "trainable": true, "dtype": "float32", "units": 32, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 4}, "bias_initializer": {"class_name": "Zeros", "config": {}}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_1", "inbound_nodes": [[["dense", 0, 0, {}]]]}, {"class_name": "Dense", "config": {"name": "dense_2", "trainable": true, "dtype": "float32", "units": 32, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 4}, "bias_initializer": {"class_name": "Zeros", "config": {}}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_2", "inbound_nodes": [[["dense_1", 0, 0, {}]]]}, {"class_name": "Dense", "config": {"name": "dense_3", "trainable": true, "dtype": "float32", "units": 1, "activation": "tanh", "use_bias": true, "kernel_initializer": {"class_name": "HeUniform", "config": {"seed": null}}, "bias_initializer": {"class_name": "Zeros", "config": {}}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_3", "inbound_nodes": [[["dense_2", 0, 0, {}]]]}, {"class_name": "Activation", "config": {"name": "v_output", "trainable": true, "dtype": "float32", "activation": "tanh"}, "name": "v_output", "inbound_nodes": [[["dense_3", 0, 0, {}]]]}, {"class_name": "Dense", "config": {"name": "dense_4", "trainable": true, "dtype": "float32", "units": 32, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 13}, "bias_initializer": {"class_name": "Zeros", "config": {}}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_4", "inbound_nodes": [[["dense", 1, 0, {}]]]}, {"class_name": "TFOpLambda", "config": {"name": "tf.__operators__.add", "trainable": true, "dtype": "float32", "function": "__operators__.add"}, "name": "tf.__operators__.add", "inbound_nodes": [["v_output", 0, 0, {"y": 1, "name": null}]]}, {"class_name": "Dense", "config": {"name": "dense_5", "trainable": true, "dtype": "float32", "units": 32, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 13}, "bias_initializer": {"class_name": "Zeros", "config": {}}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_5", "inbound_nodes": [[["dense_4", 0, 0, {}]]]}, {"class_name": "TFOpLambda", "config": {"name": "tf.math.truediv", "trainable": true, "dtype": "float32", "function": "math.truediv"}, "name": "tf.math.truediv", "inbound_nodes": [["tf.__operators__.add", 0, 0, {"y": 2, "name": null}]]}, {"class_name": "Dense", "config": {"name": "dense_6", "trainable": true, "dtype": "float32", "units": 1, "activation": "tanh", "use_bias": true, "kernel_initializer": {"class_name": "HeUniform", "config": {"seed": null}}, "bias_initializer": {"class_name": "Zeros", "config": {}}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_6", "inbound_nodes": [[["dense_5", 0, 0, {}]]]}, {"class_name": "TFOpLambda", "config": {"name": "tf.math.multiply", "trainable": true, "dtype": "float32", "function": "math.multiply"}, "name": "tf.math.multiply", "inbound_nodes": [["tf.math.truediv", 0, 0, {"y": 9, "name": null}]]}, {"class_name": "Activation", "config": {"name": "w_output", "trainable": true, "dtype": "float32", "activation": "tanh"}, "name": "w_output", "inbound_nodes": [[["dense_6", 0, 0, {}]]]}, {"class_name": "TFOpLambda", "config": {"name": "tf.__operators__.add_1", "trainable": true, "dtype": "float32", "function": "__operators__.add"}, "name": "tf.__operators__.add_1", "inbound_nodes": [["tf.math.multiply", 0, 0, {"y": 1, "name": null}]]}, {"class_name": "TFOpLambda", "config": {"name": "tf.math.multiply_1", "trainable": true, "dtype": "float32", "function": "math.multiply"}, "name": "tf.math.multiply_1", "inbound_nodes": [["w_output", 0, 0, {"y": 1.5, "name": null}]]}], "input_layers": [["input_1", 0, 0]], "output_layers": [["tf.__operators__.add_1", 0, 0], ["tf.math.multiply_1", 0, 0]]}, "shared_object_id": 27, "input_spec": [{"class_name": "InputSpec", "config": {"dtype": null, "shape": {"class_name": "__tuple__", "items": [null, 8]}, "ndim": 2, "max_ndim": null, "min_ndim": null, "axes": {}}}], "build_input_shape": {"class_name": "TensorShape", "items": [null, 8]}, "is_graph_network": true, "full_save_spec": {"class_name": "__tuple__", "items": [[{"class_name": "TypeSpec", "type_spec": "tf.TensorSpec", "serialized": [{"class_name": "TensorShape", "items": [null, 8]}, "float32", "input_1"]}], {}]}, "save_spec": {"class_name": "TypeSpec", "type_spec": "tf.TensorSpec", "serialized": [{"class_name": "TensorShape", "items": [null, 8]}, "float32", "input_1"]}, "keras_version": "2.11.0", "backend": "tensorflow", "model_config": {"class_name": "Functional", "config": {"name": "continuous_two_actions", "layers": [{"class_name": "InputLayer", "config": {"batch_input_shape": {"class_name": "__tuple__", "items": [null, 8]}, "dtype": "float32", "sparse": false, "ragged": false, "name": "input_1"}, "name": "input_1", "inbound_nodes": [], "shared_object_id": 0}, {"class_name": "Dense", "config": {"name": "dense", "trainable": true, "dtype": "float32", "units": 10, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 1}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 2}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense", "inbound_nodes": [[["input_1", 0, 0, {}]], [["input_1", 0, 0, {}]]], "shared_object_id": 3}, {"class_name": "Dense", "config": {"name": "dense_1", "trainable": true, "dtype": "float32", "units": 32, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 4}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 5}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_1", "inbound_nodes": [[["dense", 0, 0, {}]]], "shared_object_id": 6}, {"class_name": "Dense", "config": {"name": "dense_2", "trainable": true, "dtype": "float32", "units": 32, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 4}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 7}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_2", "inbound_nodes": [[["dense_1", 0, 0, {}]]], "shared_object_id": 8}, {"class_name": "Dense", "config": {"name": "dense_3", "trainable": true, "dtype": "float32", "units": 1, "activation": "tanh", "use_bias": true, "kernel_initializer": {"class_name": "HeUniform", "config": {"seed": null}, "shared_object_id": 9}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 10}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_3", "inbound_nodes": [[["dense_2", 0, 0, {}]]], "shared_object_id": 11}, {"class_name": "Activation", "config": {"name": "v_output", "trainable": true, "dtype": "float32", "activation": "tanh"}, "name": "v_output", "inbound_nodes": [[["dense_3", 0, 0, {}]]], "shared_object_id": 12}, {"class_name": "Dense", "config": {"name": "dense_4", "trainable": true, "dtype": "float32", "units": 32, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 13}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 14}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_4", "inbound_nodes": [[["dense", 1, 0, {}]]], "shared_object_id": 15}, {"class_name": "TFOpLambda", "config": {"name": "tf.__operators__.add", "trainable": true, "dtype": "float32", "function": "__operators__.add"}, "name": "tf.__operators__.add", "inbound_nodes": [["v_output", 0, 0, {"y": 1, "name": null}]], "shared_object_id": 16}, {"class_name": "Dense", "config": {"name": "dense_5", "trainable": true, "dtype": "float32", "units": 32, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 13}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 17}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_5", "inbound_nodes": [[["dense_4", 0, 0, {}]]], "shared_object_id": 18}, {"class_name": "TFOpLambda", "config": {"name": "tf.math.truediv", "trainable": true, "dtype": "float32", "function": "math.truediv"}, "name": "tf.math.truediv", "inbound_nodes": [["tf.__operators__.add", 0, 0, {"y": 2, "name": null}]], "shared_object_id": 19}, {"class_name": "Dense", "config": {"name": "dense_6", "trainable": true, "dtype": "float32", "units": 1, "activation": "tanh", "use_bias": true, "kernel_initializer": {"class_name": "HeUniform", "config": {"seed": null}, "shared_object_id": 20}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 21}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_6", "inbound_nodes": [[["dense_5", 0, 0, {}]]], "shared_object_id": 22}, {"class_name": "TFOpLambda", "config": {"name": "tf.math.multiply", "trainable": true, "dtype": "float32", "function": "math.multiply"}, "name": "tf.math.multiply", "inbound_nodes": [["tf.math.truediv", 0, 0, {"y": 9, "name": null}]], "shared_object_id": 23}, {"class_name": "Activation", "config": {"name": "w_output", "trainable": true, "dtype": "float32", "activation": "tanh"}, "name": "w_output", "inbound_nodes": [[["dense_6", 0, 0, {}]]], "shared_object_id": 24}, {"class_name": "TFOpLambda", "config": {"name": "tf.__operators__.add_1", "trainable": true, "dtype": "float32", "function": "__operators__.add"}, "name": "tf.__operators__.add_1", "inbound_nodes": [["tf.math.multiply", 0, 0, {"y": 1, "name": null}]], "shared_object_id": 25}, {"class_name": "TFOpLambda", "config": {"name": "tf.math.multiply_1", "trainable": true, "dtype": "float32", "function": "math.multiply"}, "name": "tf.math.multiply_1", "inbound_nodes": [["w_output", 0, 0, {"y": 1.5, "name": null}]], "shared_object_id": 26}], "input_layers": [["input_1", 0, 0]], "output_layers": [["tf.__operators__.add_1", 0, 0], ["tf.math.multiply_1", 0, 0]]}}}2 + root.layer-0"_tf_keras_input_layer*{"class_name": "InputLayer", "name": "input_1", "dtype": "float32", "sparse": false, "ragged": false, "batch_input_shape": {"class_name": "__tuple__", "items": [null, 8]}, "config": {"batch_input_shape": {"class_name": "__tuple__", "items": [null, 8]}, "dtype": "float32", "sparse": false, "ragged": false, "name": "input_1"}}2 +root.layer_with_weights-0"_tf_keras_layer*{"name": "dense", "trainable": true, "expects_training_arg": false, "dtype": "float32", "batch_input_shape": null, "stateful": false, "must_restore_from_config": false, "preserve_input_structure_in_config": false, "autocast": true, "class_name": "Dense", "config": {"name": "dense", "trainable": true, "dtype": "float32", "units": 10, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 1}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 2}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "inbound_nodes": [[["input_1", 0, 0, {}]], [["input_1", 0, 0, {}]]], "shared_object_id": 3, "input_spec": {"class_name": "InputSpec", "config": {"dtype": null, "shape": null, "ndim": null, "max_ndim": null, "min_ndim": 2, "axes": {"-1": 8}}, "shared_object_id": 29}, "build_input_shape": {"class_name": "TensorShape", "items": [null, 8]}}2 +root.layer_with_weights-1"_tf_keras_layer*{"name": "dense_1", "trainable": true, "expects_training_arg": false, "dtype": "float32", "batch_input_shape": null, "stateful": false, "must_restore_from_config": false, "preserve_input_structure_in_config": false, "autocast": true, "class_name": "Dense", "config": {"name": "dense_1", "trainable": true, "dtype": "float32", "units": 32, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 4}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 5}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "inbound_nodes": [[["dense", 0, 0, {}]]], "shared_object_id": 6, "input_spec": {"class_name": "InputSpec", "config": {"dtype": null, "shape": null, "ndim": null, "max_ndim": null, "min_ndim": 2, "axes": {"-1": 10}}, "shared_object_id": 30}, "build_input_shape": {"class_name": "TensorShape", "items": [null, 10]}}2 +root.layer_with_weights-2"_tf_keras_layer*{"name": "dense_2", "trainable": true, "expects_training_arg": false, "dtype": "float32", "batch_input_shape": null, "stateful": false, "must_restore_from_config": false, "preserve_input_structure_in_config": false, "autocast": true, "class_name": "Dense", "config": {"name": "dense_2", "trainable": true, "dtype": "float32", "units": 32, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 4}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 7}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "inbound_nodes": [[["dense_1", 0, 0, {}]]], "shared_object_id": 8, "input_spec": {"class_name": "InputSpec", "config": {"dtype": null, "shape": null, "ndim": null, "max_ndim": null, "min_ndim": 2, "axes": {"-1": 32}}, "shared_object_id": 31}, "build_input_shape": {"class_name": "TensorShape", "items": [null, 32]}}2 +root.layer_with_weights-3"_tf_keras_layer*{"name": "dense_3", "trainable": true, "expects_training_arg": false, "dtype": "float32", "batch_input_shape": null, "stateful": false, "must_restore_from_config": false, "preserve_input_structure_in_config": false, "autocast": true, "class_name": "Dense", "config": {"name": "dense_3", "trainable": true, "dtype": "float32", "units": 1, "activation": "tanh", "use_bias": true, "kernel_initializer": {"class_name": "HeUniform", "config": {"seed": null}, "shared_object_id": 9}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 10}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "inbound_nodes": [[["dense_2", 0, 0, {}]]], "shared_object_id": 11, "input_spec": {"class_name": "InputSpec", "config": {"dtype": null, "shape": null, "ndim": null, "max_ndim": null, "min_ndim": 2, "axes": {"-1": 32}}, "shared_object_id": 32}, "build_input_shape": {"class_name": "TensorShape", "items": [null, 32]}}2 + root.layer-5"_tf_keras_layer*{"name": "v_output", "trainable": true, "expects_training_arg": false, "dtype": "float32", "batch_input_shape": null, "stateful": false, "must_restore_from_config": false, "preserve_input_structure_in_config": false, "autocast": true, "class_name": "Activation", "config": {"name": "v_output", "trainable": true, "dtype": "float32", "activation": "tanh"}, "inbound_nodes": [[["dense_3", 0, 0, {}]]], "shared_object_id": 12}2 +root.layer_with_weights-4"_tf_keras_layer*{"name": "dense_4", "trainable": true, "expects_training_arg": false, "dtype": "float32", "batch_input_shape": null, "stateful": false, "must_restore_from_config": false, "preserve_input_structure_in_config": false, "autocast": true, "class_name": "Dense", "config": {"name": "dense_4", "trainable": true, "dtype": "float32", "units": 32, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 13}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 14}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "inbound_nodes": [[["dense", 1, 0, {}]]], "shared_object_id": 15, "input_spec": {"class_name": "InputSpec", "config": {"dtype": null, "shape": null, "ndim": null, "max_ndim": null, "min_ndim": 2, "axes": {"-1": 10}}, "shared_object_id": 33}, "build_input_shape": {"class_name": "TensorShape", "items": [null, 10]}}2 + root.layer-7"_tf_keras_layer*{"name": "tf.__operators__.add", "trainable": true, "expects_training_arg": false, "dtype": "float32", "batch_input_shape": null, "stateful": false, "must_restore_from_config": true, "preserve_input_structure_in_config": true, "autocast": false, "class_name": "TFOpLambda", "config": {"name": "tf.__operators__.add", "trainable": true, "dtype": "float32", "function": "__operators__.add"}, "inbound_nodes": [["v_output", 0, 0, {"y": 1, "name": null}]], "shared_object_id": 16}2 + root.layer_with_weights-5"_tf_keras_layer*{"name": "dense_5", "trainable": true, "expects_training_arg": false, "dtype": "float32", "batch_input_shape": null, "stateful": false, "must_restore_from_config": false, "preserve_input_structure_in_config": false, "autocast": true, "class_name": "Dense", "config": {"name": "dense_5", "trainable": true, "dtype": "float32", "units": 32, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 13}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 17}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "inbound_nodes": [[["dense_4", 0, 0, {}]]], "shared_object_id": 18, "input_spec": {"class_name": "InputSpec", "config": {"dtype": null, "shape": null, "ndim": null, "max_ndim": null, "min_ndim": 2, "axes": {"-1": 32}}, "shared_object_id": 34}, "build_input_shape": {"class_name": "TensorShape", "items": [null, 32]}}2 + + root.layer-9"_tf_keras_layer*{"name": "tf.math.truediv", "trainable": true, "expects_training_arg": false, "dtype": "float32", "batch_input_shape": null, "stateful": false, "must_restore_from_config": true, "preserve_input_structure_in_config": true, "autocast": false, "class_name": "TFOpLambda", "config": {"name": "tf.math.truediv", "trainable": true, "dtype": "float32", "function": "math.truediv"}, "inbound_nodes": [["tf.__operators__.add", 0, 0, {"y": 2, "name": null}]], "shared_object_id": 19}2 + root.layer_with_weights-6"_tf_keras_layer*{"name": "dense_6", "trainable": true, "expects_training_arg": false, "dtype": "float32", "batch_input_shape": null, "stateful": false, "must_restore_from_config": false, "preserve_input_structure_in_config": false, "autocast": true, "class_name": "Dense", "config": {"name": "dense_6", "trainable": true, "dtype": "float32", "units": 1, "activation": "tanh", "use_bias": true, "kernel_initializer": {"class_name": "HeUniform", "config": {"seed": null}, "shared_object_id": 20}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 21}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "inbound_nodes": [[["dense_5", 0, 0, {}]]], "shared_object_id": 22, "input_spec": {"class_name": "InputSpec", "config": {"dtype": null, "shape": null, "ndim": null, "max_ndim": null, "min_ndim": 2, "axes": {"-1": 32}}, "shared_object_id": 35}, "build_input_shape": {"class_name": "TensorShape", "items": [null, 32]}}2 +  root.layer-11"_tf_keras_layer*{"name": "tf.math.multiply", "trainable": true, "expects_training_arg": false, "dtype": "float32", "batch_input_shape": null, "stateful": false, "must_restore_from_config": true, "preserve_input_structure_in_config": true, "autocast": false, "class_name": "TFOpLambda", "config": {"name": "tf.math.multiply", "trainable": true, "dtype": "float32", "function": "math.multiply"}, "inbound_nodes": [["tf.math.truediv", 0, 0, {"y": 9, "name": null}]], "shared_object_id": 23}2 +  root.layer-12"_tf_keras_layer*{"name": "w_output", "trainable": true, "expects_training_arg": false, "dtype": "float32", "batch_input_shape": null, "stateful": false, "must_restore_from_config": false, "preserve_input_structure_in_config": false, "autocast": true, "class_name": "Activation", "config": {"name": "w_output", "trainable": true, "dtype": "float32", "activation": "tanh"}, "inbound_nodes": [[["dense_6", 0, 0, {}]]], "shared_object_id": 24}2 + root.layer-13"_tf_keras_layer*{"name": "tf.__operators__.add_1", "trainable": true, "expects_training_arg": false, "dtype": "float32", "batch_input_shape": null, "stateful": false, "must_restore_from_config": true, "preserve_input_structure_in_config": true, "autocast": false, "class_name": "TFOpLambda", "config": {"name": "tf.__operators__.add_1", "trainable": true, "dtype": "float32", "function": "__operators__.add"}, "inbound_nodes": [["tf.math.multiply", 0, 0, {"y": 1, "name": null}]], "shared_object_id": 25}2 + root.layer-14"_tf_keras_layer*{"name": "tf.math.multiply_1", "trainable": true, "expects_training_arg": false, "dtype": "float32", "batch_input_shape": null, "stateful": false, "must_restore_from_config": true, "preserve_input_structure_in_config": true, "autocast": false, "class_name": "TFOpLambda", "config": {"name": "tf.math.multiply_1", "trainable": true, "dtype": "float32", "function": "math.multiply"}, "inbound_nodes": [["w_output", 0, 0, {"y": 1.5, "name": null}]], "shared_object_id": 26}2 \ No newline at end of file diff --git a/behavior_metrics/models/gazebo/rl_models/ddpg/20231104-003119_LAPCOMPLETEDCircuit-simple_States-sp5_Actions-continuous_BATCH_Rewards-followline_center_MaxReward-3096_Epoch-277/ACTOR/saved_model.pb b/behavior_metrics/models/gazebo/rl_models/ddpg/20231104-003119_LAPCOMPLETEDCircuit-simple_States-sp5_Actions-continuous_BATCH_Rewards-followline_center_MaxReward-3096_Epoch-277/ACTOR/saved_model.pb new file mode 100644 index 00000000..b6532985 Binary files /dev/null and b/behavior_metrics/models/gazebo/rl_models/ddpg/20231104-003119_LAPCOMPLETEDCircuit-simple_States-sp5_Actions-continuous_BATCH_Rewards-followline_center_MaxReward-3096_Epoch-277/ACTOR/saved_model.pb differ diff --git a/behavior_metrics/models/gazebo/rl_models/ddpg/20231104-003119_LAPCOMPLETEDCircuit-simple_States-sp5_Actions-continuous_BATCH_Rewards-followline_center_MaxReward-3096_Epoch-277/ACTOR/variables/variables.data-00000-of-00001 b/behavior_metrics/models/gazebo/rl_models/ddpg/20231104-003119_LAPCOMPLETEDCircuit-simple_States-sp5_Actions-continuous_BATCH_Rewards-followline_center_MaxReward-3096_Epoch-277/ACTOR/variables/variables.data-00000-of-00001 new file mode 100644 index 00000000..9ea5fd6c Binary files /dev/null and b/behavior_metrics/models/gazebo/rl_models/ddpg/20231104-003119_LAPCOMPLETEDCircuit-simple_States-sp5_Actions-continuous_BATCH_Rewards-followline_center_MaxReward-3096_Epoch-277/ACTOR/variables/variables.data-00000-of-00001 differ diff --git a/behavior_metrics/models/gazebo/rl_models/ddpg/20231104-003119_LAPCOMPLETEDCircuit-simple_States-sp5_Actions-continuous_BATCH_Rewards-followline_center_MaxReward-3096_Epoch-277/ACTOR/variables/variables.index b/behavior_metrics/models/gazebo/rl_models/ddpg/20231104-003119_LAPCOMPLETEDCircuit-simple_States-sp5_Actions-continuous_BATCH_Rewards-followline_center_MaxReward-3096_Epoch-277/ACTOR/variables/variables.index new file mode 100644 index 00000000..7fe519b9 Binary files /dev/null and b/behavior_metrics/models/gazebo/rl_models/ddpg/20231104-003119_LAPCOMPLETEDCircuit-simple_States-sp5_Actions-continuous_BATCH_Rewards-followline_center_MaxReward-3096_Epoch-277/ACTOR/variables/variables.index differ diff --git a/behavior_metrics/models/gazebo/rl_models/ddpg/20231104-003119_LAPCOMPLETEDCircuit-simple_States-sp5_Actions-continuous_BATCH_Rewards-followline_center_MaxReward-3096_Epoch-277/CRITIC/fingerprint.pb b/behavior_metrics/models/gazebo/rl_models/ddpg/20231104-003119_LAPCOMPLETEDCircuit-simple_States-sp5_Actions-continuous_BATCH_Rewards-followline_center_MaxReward-3096_Epoch-277/CRITIC/fingerprint.pb new file mode 100644 index 00000000..affe7315 Binary files /dev/null and b/behavior_metrics/models/gazebo/rl_models/ddpg/20231104-003119_LAPCOMPLETEDCircuit-simple_States-sp5_Actions-continuous_BATCH_Rewards-followline_center_MaxReward-3096_Epoch-277/CRITIC/fingerprint.pb differ diff --git a/behavior_metrics/models/gazebo/rl_models/ddpg/20231104-003119_LAPCOMPLETEDCircuit-simple_States-sp5_Actions-continuous_BATCH_Rewards-followline_center_MaxReward-3096_Epoch-277/CRITIC/keras_metadata.pb b/behavior_metrics/models/gazebo/rl_models/ddpg/20231104-003119_LAPCOMPLETEDCircuit-simple_States-sp5_Actions-continuous_BATCH_Rewards-followline_center_MaxReward-3096_Epoch-277/CRITIC/keras_metadata.pb new file mode 100644 index 00000000..307b9a6e --- /dev/null +++ b/behavior_metrics/models/gazebo/rl_models/ddpg/20231104-003119_LAPCOMPLETEDCircuit-simple_States-sp5_Actions-continuous_BATCH_Rewards-followline_center_MaxReward-3096_Epoch-277/CRITIC/keras_metadata.pb @@ -0,0 +1,13 @@ + +Rroot"_tf_keras_network*R{"name": "model", "trainable": true, "expects_training_arg": true, "dtype": "float32", "batch_input_shape": null, "must_restore_from_config": false, "preserve_input_structure_in_config": false, "autocast": false, "class_name": "Functional", "config": {"name": "model", "layers": [{"class_name": "InputLayer", "config": {"batch_input_shape": {"class_name": "__tuple__", "items": [null, 8]}, "dtype": "float32", "sparse": false, "ragged": false, "name": "input_2"}, "name": "input_2", "inbound_nodes": []}, {"class_name": "InputLayer", "config": {"batch_input_shape": {"class_name": "__tuple__", "items": [null, 1]}, "dtype": "float32", "sparse": false, "ragged": false, "name": "input_3"}, "name": "input_3", "inbound_nodes": []}, {"class_name": "InputLayer", "config": {"batch_input_shape": {"class_name": "__tuple__", "items": [null, 1]}, "dtype": "float32", "sparse": false, "ragged": false, "name": "input_4"}, "name": "input_4", "inbound_nodes": []}, {"class_name": "Dense", "config": {"name": "dense_7", "trainable": true, "dtype": "float32", "units": 64, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}}, "bias_initializer": {"class_name": "Zeros", "config": {}}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_7", "inbound_nodes": [[["input_2", 0, 0, {}]]]}, {"class_name": "Dense", "config": {"name": "dense_8", "trainable": true, "dtype": "float32", "units": 32, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}}, "bias_initializer": {"class_name": "Zeros", "config": {}}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_8", "inbound_nodes": [[["input_3", 0, 0, {}]]]}, {"class_name": "Dense", "config": {"name": "dense_9", "trainable": true, "dtype": "float32", "units": 32, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}}, "bias_initializer": {"class_name": "Zeros", "config": {}}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_9", "inbound_nodes": [[["input_4", 0, 0, {}]]]}, {"class_name": "Concatenate", "config": {"name": "concatenate", "trainable": true, "dtype": "float32", "axis": -1}, "name": "concatenate", "inbound_nodes": [[["dense_7", 0, 0, {}], ["dense_8", 0, 0, {}], ["dense_9", 0, 0, {}]]]}, {"class_name": "Dense", "config": {"name": "dense_10", "trainable": true, "dtype": "float32", "units": 256, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}}, "bias_initializer": {"class_name": "Zeros", "config": {}}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_10", "inbound_nodes": [[["concatenate", 0, 0, {}]]]}, {"class_name": "Dense", "config": {"name": "dense_11", "trainable": true, "dtype": "float32", "units": 256, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}}, "bias_initializer": {"class_name": "Zeros", "config": {}}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_11", "inbound_nodes": [[["dense_10", 0, 0, {}]]]}, {"class_name": "Dense", "config": {"name": "dense_12", "trainable": true, "dtype": "float32", "units": 1, "activation": "linear", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}}, "bias_initializer": {"class_name": "Zeros", "config": {}}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_12", "inbound_nodes": [[["dense_11", 0, 0, {}]]]}], "input_layers": [["input_2", 0, 0], ["input_3", 0, 0], ["input_4", 0, 0]], "output_layers": [["dense_12", 0, 0]]}, "shared_object_id": 22, "input_spec": [{"class_name": "InputSpec", "config": {"dtype": null, "shape": {"class_name": "__tuple__", "items": [null, 8]}, "ndim": 2, "max_ndim": null, "min_ndim": null, "axes": {}}}, {"class_name": "InputSpec", "config": {"dtype": null, "shape": {"class_name": "__tuple__", "items": [null, 1]}, "ndim": 2, "max_ndim": null, "min_ndim": null, "axes": {}}}, {"class_name": "InputSpec", "config": {"dtype": null, "shape": {"class_name": "__tuple__", "items": [null, 1]}, "ndim": 2, "max_ndim": null, "min_ndim": null, "axes": {}}}], "build_input_shape": [{"class_name": "TensorShape", "items": [null, 8]}, {"class_name": "TensorShape", "items": [null, 1]}, {"class_name": "TensorShape", "items": [null, 1]}], "is_graph_network": true, "full_save_spec": {"class_name": "__tuple__", "items": [[[{"class_name": "TypeSpec", "type_spec": "tf.TensorSpec", "serialized": [{"class_name": "TensorShape", "items": [null, 8]}, "float32", "input_2"]}, {"class_name": "TypeSpec", "type_spec": "tf.TensorSpec", "serialized": [{"class_name": "TensorShape", "items": [null, 1]}, "float32", "input_3"]}, {"class_name": "TypeSpec", "type_spec": "tf.TensorSpec", "serialized": [{"class_name": "TensorShape", "items": [null, 1]}, "float32", "input_4"]}]], {}]}, "save_spec": [{"class_name": "TypeSpec", "type_spec": "tf.TensorSpec", "serialized": [{"class_name": "TensorShape", "items": [null, 8]}, "float32", "input_2"]}, {"class_name": "TypeSpec", "type_spec": "tf.TensorSpec", "serialized": [{"class_name": "TensorShape", "items": [null, 1]}, "float32", "input_3"]}, {"class_name": "TypeSpec", "type_spec": "tf.TensorSpec", "serialized": [{"class_name": "TensorShape", "items": [null, 1]}, "float32", "input_4"]}], "keras_version": "2.11.0", "backend": "tensorflow", "model_config": {"class_name": "Functional", "config": {"name": "model", "layers": [{"class_name": "InputLayer", "config": {"batch_input_shape": {"class_name": "__tuple__", "items": [null, 8]}, "dtype": "float32", "sparse": false, "ragged": false, "name": "input_2"}, "name": "input_2", "inbound_nodes": [], "shared_object_id": 0}, {"class_name": "InputLayer", "config": {"batch_input_shape": {"class_name": "__tuple__", "items": [null, 1]}, "dtype": "float32", "sparse": false, "ragged": false, "name": "input_3"}, "name": "input_3", "inbound_nodes": [], "shared_object_id": 1}, {"class_name": "InputLayer", "config": {"batch_input_shape": {"class_name": "__tuple__", "items": [null, 1]}, "dtype": "float32", "sparse": false, "ragged": false, "name": "input_4"}, "name": "input_4", "inbound_nodes": [], "shared_object_id": 2}, {"class_name": "Dense", "config": {"name": "dense_7", "trainable": true, "dtype": "float32", "units": 64, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 3}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 4}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_7", "inbound_nodes": [[["input_2", 0, 0, {}]]], "shared_object_id": 5}, {"class_name": "Dense", "config": {"name": "dense_8", "trainable": true, "dtype": "float32", "units": 32, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 6}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 7}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_8", "inbound_nodes": [[["input_3", 0, 0, {}]]], "shared_object_id": 8}, {"class_name": "Dense", "config": {"name": "dense_9", "trainable": true, "dtype": "float32", "units": 32, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 9}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 10}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_9", "inbound_nodes": [[["input_4", 0, 0, {}]]], "shared_object_id": 11}, {"class_name": "Concatenate", "config": {"name": "concatenate", "trainable": true, "dtype": "float32", "axis": -1}, "name": "concatenate", "inbound_nodes": [[["dense_7", 0, 0, {}], ["dense_8", 0, 0, {}], ["dense_9", 0, 0, {}]]], "shared_object_id": 12}, {"class_name": "Dense", "config": {"name": "dense_10", "trainable": true, "dtype": "float32", "units": 256, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 13}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 14}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_10", "inbound_nodes": [[["concatenate", 0, 0, {}]]], "shared_object_id": 15}, {"class_name": "Dense", "config": {"name": "dense_11", "trainable": true, "dtype": "float32", "units": 256, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 16}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 17}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_11", "inbound_nodes": [[["dense_10", 0, 0, {}]]], "shared_object_id": 18}, {"class_name": "Dense", "config": {"name": "dense_12", "trainable": true, "dtype": "float32", "units": 1, "activation": "linear", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 19}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 20}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_12", "inbound_nodes": [[["dense_11", 0, 0, {}]]], "shared_object_id": 21}], "input_layers": [["input_2", 0, 0], ["input_3", 0, 0], ["input_4", 0, 0]], "output_layers": [["dense_12", 0, 0]]}}}2 + root.layer-0"_tf_keras_input_layer*{"class_name": "InputLayer", "name": "input_2", "dtype": "float32", "sparse": false, "ragged": false, "batch_input_shape": {"class_name": "__tuple__", "items": [null, 8]}, "config": {"batch_input_shape": {"class_name": "__tuple__", "items": [null, 8]}, "dtype": "float32", "sparse": false, "ragged": false, "name": "input_2"}}2 + root.layer-1"_tf_keras_input_layer*{"class_name": "InputLayer", "name": "input_3", "dtype": "float32", "sparse": false, "ragged": false, "batch_input_shape": {"class_name": "__tuple__", "items": [null, 1]}, "config": {"batch_input_shape": {"class_name": "__tuple__", "items": [null, 1]}, "dtype": "float32", "sparse": false, "ragged": false, "name": "input_3"}}2 + root.layer-2"_tf_keras_input_layer*{"class_name": "InputLayer", "name": "input_4", "dtype": "float32", "sparse": false, "ragged": false, "batch_input_shape": {"class_name": "__tuple__", "items": [null, 1]}, "config": {"batch_input_shape": {"class_name": "__tuple__", "items": [null, 1]}, "dtype": "float32", "sparse": false, "ragged": false, "name": "input_4"}}2 +root.layer_with_weights-0"_tf_keras_layer*{"name": "dense_7", "trainable": true, "expects_training_arg": false, "dtype": "float32", "batch_input_shape": null, "stateful": false, "must_restore_from_config": false, "preserve_input_structure_in_config": false, "autocast": true, "class_name": "Dense", "config": {"name": "dense_7", "trainable": true, "dtype": "float32", "units": 64, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 3}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 4}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "inbound_nodes": [[["input_2", 0, 0, {}]]], "shared_object_id": 5, "input_spec": {"class_name": "InputSpec", "config": {"dtype": null, "shape": null, "ndim": null, "max_ndim": null, "min_ndim": 2, "axes": {"-1": 8}}, "shared_object_id": 26}, "build_input_shape": {"class_name": "TensorShape", "items": [null, 8]}}2 +root.layer_with_weights-1"_tf_keras_layer*{"name": "dense_8", "trainable": true, "expects_training_arg": false, "dtype": "float32", "batch_input_shape": null, "stateful": false, "must_restore_from_config": false, "preserve_input_structure_in_config": false, "autocast": true, "class_name": "Dense", "config": {"name": "dense_8", "trainable": true, "dtype": "float32", "units": 32, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 6}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 7}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "inbound_nodes": [[["input_3", 0, 0, {}]]], "shared_object_id": 8, "input_spec": {"class_name": "InputSpec", "config": {"dtype": null, "shape": null, "ndim": null, "max_ndim": null, "min_ndim": 2, "axes": {"-1": 1}}, "shared_object_id": 27}, "build_input_shape": {"class_name": "TensorShape", "items": [null, 1]}}2 +root.layer_with_weights-2"_tf_keras_layer*{"name": "dense_9", "trainable": true, "expects_training_arg": false, "dtype": "float32", "batch_input_shape": null, "stateful": false, "must_restore_from_config": false, "preserve_input_structure_in_config": false, "autocast": true, "class_name": "Dense", "config": {"name": "dense_9", "trainable": true, "dtype": "float32", "units": 32, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 9}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 10}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "inbound_nodes": [[["input_4", 0, 0, {}]]], "shared_object_id": 11, "input_spec": {"class_name": "InputSpec", "config": {"dtype": null, "shape": null, "ndim": null, "max_ndim": null, "min_ndim": 2, "axes": {"-1": 1}}, "shared_object_id": 28}, "build_input_shape": {"class_name": "TensorShape", "items": [null, 1]}}2 + root.layer-6"_tf_keras_layer*{"name": "concatenate", "trainable": true, "expects_training_arg": false, "dtype": "float32", "batch_input_shape": null, "stateful": false, "must_restore_from_config": false, "preserve_input_structure_in_config": false, "autocast": true, "class_name": "Concatenate", "config": {"name": "concatenate", "trainable": true, "dtype": "float32", "axis": -1}, "inbound_nodes": [[["dense_7", 0, 0, {}], ["dense_8", 0, 0, {}], ["dense_9", 0, 0, {}]]], "shared_object_id": 12, "build_input_shape": [{"class_name": "TensorShape", "items": [null, 64]}, {"class_name": "TensorShape", "items": [null, 32]}, {"class_name": "TensorShape", "items": [null, 32]}]}2 +root.layer_with_weights-3"_tf_keras_layer*{"name": "dense_10", "trainable": true, "expects_training_arg": false, "dtype": "float32", "batch_input_shape": null, "stateful": false, "must_restore_from_config": false, "preserve_input_structure_in_config": false, "autocast": true, "class_name": "Dense", "config": {"name": "dense_10", "trainable": true, "dtype": "float32", "units": 256, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 13}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 14}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "inbound_nodes": [[["concatenate", 0, 0, {}]]], "shared_object_id": 15, "input_spec": {"class_name": "InputSpec", "config": {"dtype": null, "shape": null, "ndim": null, "max_ndim": null, "min_ndim": 2, "axes": {"-1": 128}}, "shared_object_id": 29}, "build_input_shape": {"class_name": "TensorShape", "items": [null, 128]}}2 + root.layer_with_weights-4"_tf_keras_layer*{"name": "dense_11", "trainable": true, "expects_training_arg": false, "dtype": "float32", "batch_input_shape": null, "stateful": false, "must_restore_from_config": false, "preserve_input_structure_in_config": false, "autocast": true, "class_name": "Dense", "config": {"name": "dense_11", "trainable": true, "dtype": "float32", "units": 256, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 16}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 17}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "inbound_nodes": [[["dense_10", 0, 0, {}]]], "shared_object_id": 18, "input_spec": {"class_name": "InputSpec", "config": {"dtype": null, "shape": null, "ndim": null, "max_ndim": null, "min_ndim": 2, "axes": {"-1": 256}}, "shared_object_id": 30}, "build_input_shape": {"class_name": "TensorShape", "items": [null, 256]}}2 + +root.layer_with_weights-5"_tf_keras_layer*{"name": "dense_12", "trainable": true, "expects_training_arg": false, "dtype": "float32", "batch_input_shape": null, "stateful": false, "must_restore_from_config": false, "preserve_input_structure_in_config": false, "autocast": true, "class_name": "Dense", "config": {"name": "dense_12", "trainable": true, "dtype": "float32", "units": 1, "activation": "linear", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 19}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 20}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "inbound_nodes": [[["dense_11", 0, 0, {}]]], "shared_object_id": 21, "input_spec": {"class_name": "InputSpec", "config": {"dtype": null, "shape": null, "ndim": null, "max_ndim": null, "min_ndim": 2, "axes": {"-1": 256}}, "shared_object_id": 31}, "build_input_shape": {"class_name": "TensorShape", "items": [null, 256]}}2 \ No newline at end of file diff --git a/behavior_metrics/models/gazebo/rl_models/ddpg/20231104-003119_LAPCOMPLETEDCircuit-simple_States-sp5_Actions-continuous_BATCH_Rewards-followline_center_MaxReward-3096_Epoch-277/CRITIC/saved_model.pb b/behavior_metrics/models/gazebo/rl_models/ddpg/20231104-003119_LAPCOMPLETEDCircuit-simple_States-sp5_Actions-continuous_BATCH_Rewards-followline_center_MaxReward-3096_Epoch-277/CRITIC/saved_model.pb new file mode 100644 index 00000000..0ad42f1b Binary files /dev/null and b/behavior_metrics/models/gazebo/rl_models/ddpg/20231104-003119_LAPCOMPLETEDCircuit-simple_States-sp5_Actions-continuous_BATCH_Rewards-followline_center_MaxReward-3096_Epoch-277/CRITIC/saved_model.pb differ diff --git a/behavior_metrics/models/gazebo/rl_models/ddpg/20231104-003119_LAPCOMPLETEDCircuit-simple_States-sp5_Actions-continuous_BATCH_Rewards-followline_center_MaxReward-3096_Epoch-277/CRITIC/variables/variables.data-00000-of-00001 b/behavior_metrics/models/gazebo/rl_models/ddpg/20231104-003119_LAPCOMPLETEDCircuit-simple_States-sp5_Actions-continuous_BATCH_Rewards-followline_center_MaxReward-3096_Epoch-277/CRITIC/variables/variables.data-00000-of-00001 new file mode 100644 index 00000000..077d76f9 Binary files /dev/null and b/behavior_metrics/models/gazebo/rl_models/ddpg/20231104-003119_LAPCOMPLETEDCircuit-simple_States-sp5_Actions-continuous_BATCH_Rewards-followline_center_MaxReward-3096_Epoch-277/CRITIC/variables/variables.data-00000-of-00001 differ diff --git a/behavior_metrics/models/gazebo/rl_models/ddpg/20231104-003119_LAPCOMPLETEDCircuit-simple_States-sp5_Actions-continuous_BATCH_Rewards-followline_center_MaxReward-3096_Epoch-277/CRITIC/variables/variables.index b/behavior_metrics/models/gazebo/rl_models/ddpg/20231104-003119_LAPCOMPLETEDCircuit-simple_States-sp5_Actions-continuous_BATCH_Rewards-followline_center_MaxReward-3096_Epoch-277/CRITIC/variables/variables.index new file mode 100644 index 00000000..9cfd46b5 Binary files /dev/null and b/behavior_metrics/models/gazebo/rl_models/ddpg/20231104-003119_LAPCOMPLETEDCircuit-simple_States-sp5_Actions-continuous_BATCH_Rewards-followline_center_MaxReward-3096_Epoch-277/CRITIC/variables/variables.index differ diff --git a/behavior_metrics/models/gazebo/rl_models/ddpg/superfast-20231118-220658_IMPROVED_C-simple_S-sp5_A-continuous_MR-2025_E-3797/ACTOR/fingerprint.pb b/behavior_metrics/models/gazebo/rl_models/ddpg/superfast-20231118-220658_IMPROVED_C-simple_S-sp5_A-continuous_MR-2025_E-3797/ACTOR/fingerprint.pb new file mode 100644 index 00000000..dbf3567c Binary files /dev/null and b/behavior_metrics/models/gazebo/rl_models/ddpg/superfast-20231118-220658_IMPROVED_C-simple_S-sp5_A-continuous_MR-2025_E-3797/ACTOR/fingerprint.pb differ diff --git a/behavior_metrics/models/gazebo/rl_models/ddpg/superfast-20231118-220658_IMPROVED_C-simple_S-sp5_A-continuous_MR-2025_E-3797/ACTOR/keras_metadata.pb b/behavior_metrics/models/gazebo/rl_models/ddpg/superfast-20231118-220658_IMPROVED_C-simple_S-sp5_A-continuous_MR-2025_E-3797/ACTOR/keras_metadata.pb new file mode 100644 index 00000000..6d65eb1f --- /dev/null +++ b/behavior_metrics/models/gazebo/rl_models/ddpg/superfast-20231118-220658_IMPROVED_C-simple_S-sp5_A-continuous_MR-2025_E-3797/ACTOR/keras_metadata.pb @@ -0,0 +1,21 @@ + +froot"_tf_keras_network*f{"name": "continuous_two_actions", "trainable": true, "expects_training_arg": true, "dtype": "float32", "batch_input_shape": null, "must_restore_from_config": false, "preserve_input_structure_in_config": false, "autocast": false, "class_name": "Functional", "config": {"name": "continuous_two_actions", "layers": [{"class_name": "InputLayer", "config": {"batch_input_shape": {"class_name": "__tuple__", "items": [null, 8]}, "dtype": "float32", "sparse": false, "ragged": false, "name": "input_1"}, "name": "input_1", "inbound_nodes": []}, {"class_name": "Dense", "config": {"name": "dense", "trainable": true, "dtype": "float32", "units": 16, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}}, "bias_initializer": {"class_name": "Zeros", "config": {}}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense", "inbound_nodes": [[["input_1", 0, 0, {}]], [["input_1", 0, 0, {}]]]}, {"class_name": "Dense", "config": {"name": "dense_1", "trainable": true, "dtype": "float32", "units": 16, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 4}, "bias_initializer": {"class_name": "Zeros", "config": {}}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_1", "inbound_nodes": [[["dense", 0, 0, {}]]]}, {"class_name": "Dense", "config": {"name": "dense_2", "trainable": true, "dtype": "float32", "units": 16, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 4}, "bias_initializer": {"class_name": "Zeros", "config": {}}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_2", "inbound_nodes": [[["dense_1", 0, 0, {}]]]}, {"class_name": "Dense", "config": {"name": "dense_3", "trainable": true, "dtype": "float32", "units": 1, "activation": "tanh", "use_bias": true, "kernel_initializer": {"class_name": "HeUniform", "config": {"seed": null}}, "bias_initializer": {"class_name": "Zeros", "config": {}}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_3", "inbound_nodes": [[["dense_2", 0, 0, {}]]]}, {"class_name": "Activation", "config": {"name": "v_output", "trainable": true, "dtype": "float32", "activation": "tanh"}, "name": "v_output", "inbound_nodes": [[["dense_3", 0, 0, {}]]]}, {"class_name": "Dense", "config": {"name": "dense_4", "trainable": true, "dtype": "float32", "units": 16, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 13}, "bias_initializer": {"class_name": "Zeros", "config": {}}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_4", "inbound_nodes": [[["dense", 1, 0, {}]]]}, {"class_name": "TFOpLambda", "config": {"name": "tf.__operators__.add", "trainable": true, "dtype": "float32", "function": "__operators__.add"}, "name": "tf.__operators__.add", "inbound_nodes": [["v_output", 0, 0, {"y": 1, "name": null}]]}, {"class_name": "Dense", "config": {"name": "dense_5", "trainable": true, "dtype": "float32", "units": 16, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 13}, "bias_initializer": {"class_name": "Zeros", "config": {}}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_5", "inbound_nodes": [[["dense_4", 0, 0, {}]]]}, {"class_name": "TFOpLambda", "config": {"name": "tf.math.truediv", "trainable": true, "dtype": "float32", "function": "math.truediv"}, "name": "tf.math.truediv", "inbound_nodes": [["tf.__operators__.add", 0, 0, {"y": 2, "name": null}]]}, {"class_name": "Dense", "config": {"name": "dense_6", "trainable": true, "dtype": "float32", "units": 1, "activation": "tanh", "use_bias": true, "kernel_initializer": {"class_name": "HeUniform", "config": {"seed": null}}, "bias_initializer": {"class_name": "Zeros", "config": {}}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_6", "inbound_nodes": [[["dense_5", 0, 0, {}]]]}, {"class_name": "TFOpLambda", "config": {"name": "tf.math.multiply", "trainable": true, "dtype": "float32", "function": "math.multiply"}, "name": "tf.math.multiply", "inbound_nodes": [["tf.math.truediv", 0, 0, {"y": 19, "name": null}]]}, {"class_name": "Activation", "config": {"name": "w_output", "trainable": true, "dtype": "float32", "activation": "tanh"}, "name": "w_output", "inbound_nodes": [[["dense_6", 0, 0, {}]]]}, {"class_name": "TFOpLambda", "config": {"name": "tf.__operators__.add_1", "trainable": true, "dtype": "float32", "function": "__operators__.add"}, "name": "tf.__operators__.add_1", "inbound_nodes": [["tf.math.multiply", 0, 0, {"y": 1, "name": null}]]}, {"class_name": "TFOpLambda", "config": {"name": "tf.math.multiply_1", "trainable": true, "dtype": "float32", "function": "math.multiply"}, "name": "tf.math.multiply_1", "inbound_nodes": [["w_output", 0, 0, {"y": 2, "name": null}]]}], "input_layers": [["input_1", 0, 0]], "output_layers": [["tf.__operators__.add_1", 0, 0], ["tf.math.multiply_1", 0, 0]]}, "shared_object_id": 27, "input_spec": [{"class_name": "InputSpec", "config": {"dtype": null, "shape": {"class_name": "__tuple__", "items": [null, 8]}, "ndim": 2, "max_ndim": null, "min_ndim": null, "axes": {}}}], "build_input_shape": {"class_name": "TensorShape", "items": [null, 8]}, "is_graph_network": true, "full_save_spec": {"class_name": "__tuple__", "items": [[{"class_name": "TypeSpec", "type_spec": "tf.TensorSpec", "serialized": [{"class_name": "TensorShape", "items": [null, 8]}, "float32", "input_1"]}], {}]}, "save_spec": {"class_name": "TypeSpec", "type_spec": "tf.TensorSpec", "serialized": [{"class_name": "TensorShape", "items": [null, 8]}, "float32", "input_1"]}, "keras_version": "2.11.0", "backend": "tensorflow", "model_config": {"class_name": "Functional", "config": {"name": "continuous_two_actions", "layers": [{"class_name": "InputLayer", "config": {"batch_input_shape": {"class_name": "__tuple__", "items": [null, 8]}, "dtype": "float32", "sparse": false, "ragged": false, "name": "input_1"}, "name": "input_1", "inbound_nodes": [], "shared_object_id": 0}, {"class_name": "Dense", "config": {"name": "dense", "trainable": true, "dtype": "float32", "units": 16, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 1}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 2}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense", "inbound_nodes": [[["input_1", 0, 0, {}]], [["input_1", 0, 0, {}]]], "shared_object_id": 3}, {"class_name": "Dense", "config": {"name": "dense_1", "trainable": true, "dtype": "float32", "units": 16, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 4}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 5}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_1", "inbound_nodes": [[["dense", 0, 0, {}]]], "shared_object_id": 6}, {"class_name": "Dense", "config": {"name": "dense_2", "trainable": true, "dtype": "float32", "units": 16, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 4}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 7}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_2", "inbound_nodes": [[["dense_1", 0, 0, {}]]], "shared_object_id": 8}, {"class_name": "Dense", "config": {"name": "dense_3", "trainable": true, "dtype": "float32", "units": 1, "activation": "tanh", "use_bias": true, "kernel_initializer": {"class_name": "HeUniform", "config": {"seed": null}, "shared_object_id": 9}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 10}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_3", "inbound_nodes": [[["dense_2", 0, 0, {}]]], "shared_object_id": 11}, {"class_name": "Activation", "config": {"name": "v_output", "trainable": true, "dtype": "float32", "activation": "tanh"}, "name": "v_output", "inbound_nodes": [[["dense_3", 0, 0, {}]]], "shared_object_id": 12}, {"class_name": "Dense", "config": {"name": "dense_4", "trainable": true, "dtype": "float32", "units": 16, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 13}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 14}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_4", "inbound_nodes": [[["dense", 1, 0, {}]]], "shared_object_id": 15}, {"class_name": "TFOpLambda", "config": {"name": "tf.__operators__.add", "trainable": true, "dtype": "float32", "function": "__operators__.add"}, "name": "tf.__operators__.add", "inbound_nodes": [["v_output", 0, 0, {"y": 1, "name": null}]], "shared_object_id": 16}, {"class_name": "Dense", "config": {"name": "dense_5", "trainable": true, "dtype": "float32", "units": 16, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 13}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 17}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_5", "inbound_nodes": [[["dense_4", 0, 0, {}]]], "shared_object_id": 18}, {"class_name": "TFOpLambda", "config": {"name": "tf.math.truediv", "trainable": true, "dtype": "float32", "function": "math.truediv"}, "name": "tf.math.truediv", "inbound_nodes": [["tf.__operators__.add", 0, 0, {"y": 2, "name": null}]], "shared_object_id": 19}, {"class_name": "Dense", "config": {"name": "dense_6", "trainable": true, "dtype": "float32", "units": 1, "activation": "tanh", "use_bias": true, "kernel_initializer": {"class_name": "HeUniform", "config": {"seed": null}, "shared_object_id": 20}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 21}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_6", "inbound_nodes": [[["dense_5", 0, 0, {}]]], "shared_object_id": 22}, {"class_name": "TFOpLambda", "config": {"name": "tf.math.multiply", "trainable": true, "dtype": "float32", "function": "math.multiply"}, "name": "tf.math.multiply", "inbound_nodes": [["tf.math.truediv", 0, 0, {"y": 19, "name": null}]], "shared_object_id": 23}, {"class_name": "Activation", "config": {"name": "w_output", "trainable": true, "dtype": "float32", "activation": "tanh"}, "name": "w_output", "inbound_nodes": [[["dense_6", 0, 0, {}]]], "shared_object_id": 24}, {"class_name": "TFOpLambda", "config": {"name": "tf.__operators__.add_1", "trainable": true, "dtype": "float32", "function": "__operators__.add"}, "name": "tf.__operators__.add_1", "inbound_nodes": [["tf.math.multiply", 0, 0, {"y": 1, "name": null}]], "shared_object_id": 25}, {"class_name": "TFOpLambda", "config": {"name": "tf.math.multiply_1", "trainable": true, "dtype": "float32", "function": "math.multiply"}, "name": "tf.math.multiply_1", "inbound_nodes": [["w_output", 0, 0, {"y": 2, "name": null}]], "shared_object_id": 26}], "input_layers": [["input_1", 0, 0]], "output_layers": [["tf.__operators__.add_1", 0, 0], ["tf.math.multiply_1", 0, 0]]}}, "training_config": {"loss": "mse", "metrics": null, "weighted_metrics": null, "loss_weights": null, "optimizer_config": {"class_name": "Custom>Adam", "config": {"name": "Adam", "weight_decay": null, "clipnorm": null, "global_clipnorm": null, "clipvalue": null, "use_ema": false, "ema_momentum": 0.99, "ema_overwrite_frequency": null, "jit_compile": true, "is_legacy_optimizer": false, "learning_rate": 0.004999999888241291, "beta_1": 0.9, "beta_2": 0.999, "epsilon": 1e-07, "amsgrad": false}}}}2 + root.layer-0"_tf_keras_input_layer*{"class_name": "InputLayer", "name": "input_1", "dtype": "float32", "sparse": false, "ragged": false, "batch_input_shape": {"class_name": "__tuple__", "items": [null, 8]}, "config": {"batch_input_shape": {"class_name": "__tuple__", "items": [null, 8]}, "dtype": "float32", "sparse": false, "ragged": false, "name": "input_1"}}2 +root.layer_with_weights-0"_tf_keras_layer*{"name": "dense", "trainable": true, "expects_training_arg": false, "dtype": "float32", "batch_input_shape": null, "stateful": false, "must_restore_from_config": false, "preserve_input_structure_in_config": false, "autocast": true, "class_name": "Dense", "config": {"name": "dense", "trainable": true, "dtype": "float32", "units": 16, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 1}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 2}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "inbound_nodes": [[["input_1", 0, 0, {}]], [["input_1", 0, 0, {}]]], "shared_object_id": 3, "input_spec": {"class_name": "InputSpec", "config": {"dtype": null, "shape": null, "ndim": null, "max_ndim": null, "min_ndim": 2, "axes": {"-1": 8}}, "shared_object_id": 29}, "build_input_shape": {"class_name": "TensorShape", "items": [null, 8]}}2 +root.layer_with_weights-1"_tf_keras_layer*{"name": "dense_1", "trainable": true, "expects_training_arg": false, "dtype": "float32", "batch_input_shape": null, "stateful": false, "must_restore_from_config": false, "preserve_input_structure_in_config": false, "autocast": true, "class_name": "Dense", "config": {"name": "dense_1", "trainable": true, "dtype": "float32", "units": 16, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 4}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 5}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "inbound_nodes": [[["dense", 0, 0, {}]]], "shared_object_id": 6, "input_spec": {"class_name": "InputSpec", "config": {"dtype": null, "shape": null, "ndim": null, "max_ndim": null, "min_ndim": 2, "axes": {"-1": 16}}, "shared_object_id": 30}, "build_input_shape": {"class_name": "TensorShape", "items": [null, 16]}}2 +root.layer_with_weights-2"_tf_keras_layer*{"name": "dense_2", "trainable": true, "expects_training_arg": false, "dtype": "float32", "batch_input_shape": null, "stateful": false, "must_restore_from_config": false, "preserve_input_structure_in_config": false, "autocast": true, "class_name": "Dense", "config": {"name": "dense_2", "trainable": true, "dtype": "float32", "units": 16, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 4}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 7}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "inbound_nodes": [[["dense_1", 0, 0, {}]]], "shared_object_id": 8, "input_spec": {"class_name": "InputSpec", "config": {"dtype": null, "shape": null, "ndim": null, "max_ndim": null, "min_ndim": 2, "axes": {"-1": 16}}, "shared_object_id": 31}, "build_input_shape": {"class_name": "TensorShape", "items": [null, 16]}}2 +root.layer_with_weights-3"_tf_keras_layer*{"name": "dense_3", "trainable": true, "expects_training_arg": false, "dtype": "float32", "batch_input_shape": null, "stateful": false, "must_restore_from_config": false, "preserve_input_structure_in_config": false, "autocast": true, "class_name": "Dense", "config": {"name": "dense_3", "trainable": true, "dtype": "float32", "units": 1, "activation": "tanh", "use_bias": true, "kernel_initializer": {"class_name": "HeUniform", "config": {"seed": null}, "shared_object_id": 9}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 10}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "inbound_nodes": [[["dense_2", 0, 0, {}]]], "shared_object_id": 11, "input_spec": {"class_name": "InputSpec", "config": {"dtype": null, "shape": null, "ndim": null, "max_ndim": null, "min_ndim": 2, "axes": {"-1": 16}}, "shared_object_id": 32}, "build_input_shape": {"class_name": "TensorShape", "items": [null, 16]}}2 + root.layer-5"_tf_keras_layer*{"name": "v_output", "trainable": true, "expects_training_arg": false, "dtype": "float32", "batch_input_shape": null, "stateful": false, "must_restore_from_config": false, "preserve_input_structure_in_config": false, "autocast": true, "class_name": "Activation", "config": {"name": "v_output", "trainable": true, "dtype": "float32", "activation": "tanh"}, "inbound_nodes": [[["dense_3", 0, 0, {}]]], "shared_object_id": 12, "build_input_shape": {"class_name": "TensorShape", "items": [null, 1]}}2 +root.layer_with_weights-4"_tf_keras_layer*{"name": "dense_4", "trainable": true, "expects_training_arg": false, "dtype": "float32", "batch_input_shape": null, "stateful": false, "must_restore_from_config": false, "preserve_input_structure_in_config": false, "autocast": true, "class_name": "Dense", "config": {"name": "dense_4", "trainable": true, "dtype": "float32", "units": 16, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 13}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 14}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "inbound_nodes": [[["dense", 1, 0, {}]]], "shared_object_id": 15, "input_spec": {"class_name": "InputSpec", "config": {"dtype": null, "shape": null, "ndim": null, "max_ndim": null, "min_ndim": 2, "axes": {"-1": 16}}, "shared_object_id": 33}, "build_input_shape": {"class_name": "TensorShape", "items": [null, 16]}}2 + root.layer-7"_tf_keras_layer*{"name": "tf.__operators__.add", "trainable": true, "expects_training_arg": false, "dtype": "float32", "batch_input_shape": null, "stateful": false, "must_restore_from_config": true, "preserve_input_structure_in_config": true, "autocast": false, "class_name": "TFOpLambda", "config": {"name": "tf.__operators__.add", "trainable": true, "dtype": "float32", "function": "__operators__.add"}, "inbound_nodes": [["v_output", 0, 0, {"y": 1, "name": null}]], "shared_object_id": 16, "build_input_shape": {"class_name": "TensorShape", "items": [null, 1]}}2 + root.layer_with_weights-5"_tf_keras_layer*{"name": "dense_5", "trainable": true, "expects_training_arg": false, "dtype": "float32", "batch_input_shape": null, "stateful": false, "must_restore_from_config": false, "preserve_input_structure_in_config": false, "autocast": true, "class_name": "Dense", "config": {"name": "dense_5", "trainable": true, "dtype": "float32", "units": 16, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 13}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 17}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "inbound_nodes": [[["dense_4", 0, 0, {}]]], "shared_object_id": 18, "input_spec": {"class_name": "InputSpec", "config": {"dtype": null, "shape": null, "ndim": null, "max_ndim": null, "min_ndim": 2, "axes": {"-1": 16}}, "shared_object_id": 34}, "build_input_shape": {"class_name": "TensorShape", "items": [null, 16]}}2 + + root.layer-9"_tf_keras_layer*{"name": "tf.math.truediv", "trainable": true, "expects_training_arg": false, "dtype": "float32", "batch_input_shape": null, "stateful": false, "must_restore_from_config": true, "preserve_input_structure_in_config": true, "autocast": false, "class_name": "TFOpLambda", "config": {"name": "tf.math.truediv", "trainable": true, "dtype": "float32", "function": "math.truediv"}, "inbound_nodes": [["tf.__operators__.add", 0, 0, {"y": 2, "name": null}]], "shared_object_id": 19, "build_input_shape": {"class_name": "TensorShape", "items": [null, 1]}}2 + root.layer_with_weights-6"_tf_keras_layer*{"name": "dense_6", "trainable": true, "expects_training_arg": false, "dtype": "float32", "batch_input_shape": null, "stateful": false, "must_restore_from_config": false, "preserve_input_structure_in_config": false, "autocast": true, "class_name": "Dense", "config": {"name": "dense_6", "trainable": true, "dtype": "float32", "units": 1, "activation": "tanh", "use_bias": true, "kernel_initializer": {"class_name": "HeUniform", "config": {"seed": null}, "shared_object_id": 20}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 21}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "inbound_nodes": [[["dense_5", 0, 0, {}]]], "shared_object_id": 22, "input_spec": {"class_name": "InputSpec", "config": {"dtype": null, "shape": null, "ndim": null, "max_ndim": null, "min_ndim": 2, "axes": {"-1": 16}}, "shared_object_id": 35}, "build_input_shape": {"class_name": "TensorShape", "items": [null, 16]}}2 +  root.layer-11"_tf_keras_layer*{"name": "tf.math.multiply", "trainable": true, "expects_training_arg": false, "dtype": "float32", "batch_input_shape": null, "stateful": false, "must_restore_from_config": true, "preserve_input_structure_in_config": true, "autocast": false, "class_name": "TFOpLambda", "config": {"name": "tf.math.multiply", "trainable": true, "dtype": "float32", "function": "math.multiply"}, "inbound_nodes": [["tf.math.truediv", 0, 0, {"y": 19, "name": null}]], "shared_object_id": 23, "build_input_shape": {"class_name": "TensorShape", "items": [null, 1]}}2 +  root.layer-12"_tf_keras_layer*{"name": "w_output", "trainable": true, "expects_training_arg": false, "dtype": "float32", "batch_input_shape": null, "stateful": false, "must_restore_from_config": false, "preserve_input_structure_in_config": false, "autocast": true, "class_name": "Activation", "config": {"name": "w_output", "trainable": true, "dtype": "float32", "activation": "tanh"}, "inbound_nodes": [[["dense_6", 0, 0, {}]]], "shared_object_id": 24, "build_input_shape": {"class_name": "TensorShape", "items": [null, 1]}}2 + root.layer-13"_tf_keras_layer*{"name": "tf.__operators__.add_1", "trainable": true, "expects_training_arg": false, "dtype": "float32", "batch_input_shape": null, "stateful": false, "must_restore_from_config": true, "preserve_input_structure_in_config": true, "autocast": false, "class_name": "TFOpLambda", "config": {"name": "tf.__operators__.add_1", "trainable": true, "dtype": "float32", "function": "__operators__.add"}, "inbound_nodes": [["tf.math.multiply", 0, 0, {"y": 1, "name": null}]], "shared_object_id": 25, "build_input_shape": {"class_name": "TensorShape", "items": [null, 1]}}2 + root.layer-14"_tf_keras_layer*{"name": "tf.math.multiply_1", "trainable": true, "expects_training_arg": false, "dtype": "float32", "batch_input_shape": null, "stateful": false, "must_restore_from_config": true, "preserve_input_structure_in_config": true, "autocast": false, "class_name": "TFOpLambda", "config": {"name": "tf.math.multiply_1", "trainable": true, "dtype": "float32", "function": "math.multiply"}, "inbound_nodes": [["w_output", 0, 0, {"y": 2, "name": null}]], "shared_object_id": 26, "build_input_shape": {"class_name": "TensorShape", "items": [null, 1]}}2 +root.keras_api.metrics.0"_tf_keras_metric*{"class_name": "Mean", "name": "loss", "dtype": "float32", "config": {"name": "loss", "dtype": "float32"}, "shared_object_id": 36}2 +root.keras_api.metrics.1"_tf_keras_metric*{"class_name": "Mean", "name": "tf.__operators__.add_1_loss", "dtype": "float32", "config": {"name": "tf.__operators__.add_1_loss", "dtype": "float32"}, "shared_object_id": 37}2 +root.keras_api.metrics.2"_tf_keras_metric*{"class_name": "Mean", "name": "tf.math.multiply_1_loss", "dtype": "float32", "config": {"name": "tf.math.multiply_1_loss", "dtype": "float32"}, "shared_object_id": 38}2 \ No newline at end of file diff --git a/behavior_metrics/models/gazebo/rl_models/ddpg/superfast-20231118-220658_IMPROVED_C-simple_S-sp5_A-continuous_MR-2025_E-3797/ACTOR/saved_model.pb b/behavior_metrics/models/gazebo/rl_models/ddpg/superfast-20231118-220658_IMPROVED_C-simple_S-sp5_A-continuous_MR-2025_E-3797/ACTOR/saved_model.pb new file mode 100644 index 00000000..ce2a3a63 Binary files /dev/null and b/behavior_metrics/models/gazebo/rl_models/ddpg/superfast-20231118-220658_IMPROVED_C-simple_S-sp5_A-continuous_MR-2025_E-3797/ACTOR/saved_model.pb differ diff --git a/behavior_metrics/models/gazebo/rl_models/ddpg/superfast-20231118-220658_IMPROVED_C-simple_S-sp5_A-continuous_MR-2025_E-3797/ACTOR/variables/variables.data-00000-of-00001 b/behavior_metrics/models/gazebo/rl_models/ddpg/superfast-20231118-220658_IMPROVED_C-simple_S-sp5_A-continuous_MR-2025_E-3797/ACTOR/variables/variables.data-00000-of-00001 new file mode 100644 index 00000000..1d25da60 Binary files /dev/null and b/behavior_metrics/models/gazebo/rl_models/ddpg/superfast-20231118-220658_IMPROVED_C-simple_S-sp5_A-continuous_MR-2025_E-3797/ACTOR/variables/variables.data-00000-of-00001 differ diff --git a/behavior_metrics/models/gazebo/rl_models/ddpg/superfast-20231118-220658_IMPROVED_C-simple_S-sp5_A-continuous_MR-2025_E-3797/ACTOR/variables/variables.index b/behavior_metrics/models/gazebo/rl_models/ddpg/superfast-20231118-220658_IMPROVED_C-simple_S-sp5_A-continuous_MR-2025_E-3797/ACTOR/variables/variables.index new file mode 100644 index 00000000..78bf10db Binary files /dev/null and b/behavior_metrics/models/gazebo/rl_models/ddpg/superfast-20231118-220658_IMPROVED_C-simple_S-sp5_A-continuous_MR-2025_E-3797/ACTOR/variables/variables.index differ diff --git a/behavior_metrics/models/gazebo/rl_models/ddpg/superfast-20231118-220658_IMPROVED_C-simple_S-sp5_A-continuous_MR-2025_E-3797/CRITIC/fingerprint.pb b/behavior_metrics/models/gazebo/rl_models/ddpg/superfast-20231118-220658_IMPROVED_C-simple_S-sp5_A-continuous_MR-2025_E-3797/CRITIC/fingerprint.pb new file mode 100644 index 00000000..23cada44 Binary files /dev/null and b/behavior_metrics/models/gazebo/rl_models/ddpg/superfast-20231118-220658_IMPROVED_C-simple_S-sp5_A-continuous_MR-2025_E-3797/CRITIC/fingerprint.pb differ diff --git a/behavior_metrics/models/gazebo/rl_models/ddpg/superfast-20231118-220658_IMPROVED_C-simple_S-sp5_A-continuous_MR-2025_E-3797/CRITIC/keras_metadata.pb b/behavior_metrics/models/gazebo/rl_models/ddpg/superfast-20231118-220658_IMPROVED_C-simple_S-sp5_A-continuous_MR-2025_E-3797/CRITIC/keras_metadata.pb new file mode 100644 index 00000000..0b90ec56 --- /dev/null +++ b/behavior_metrics/models/gazebo/rl_models/ddpg/superfast-20231118-220658_IMPROVED_C-simple_S-sp5_A-continuous_MR-2025_E-3797/CRITIC/keras_metadata.pb @@ -0,0 +1,14 @@ + +Vroot"_tf_keras_network*V{"name": "model", "trainable": true, "expects_training_arg": true, "dtype": "float32", "batch_input_shape": null, "must_restore_from_config": false, "preserve_input_structure_in_config": false, "autocast": false, "class_name": "Functional", "config": {"name": "model", "layers": [{"class_name": "InputLayer", "config": {"batch_input_shape": {"class_name": "__tuple__", "items": [null, 8]}, "dtype": "float32", "sparse": false, "ragged": false, "name": "input_2"}, "name": "input_2", "inbound_nodes": []}, {"class_name": "InputLayer", "config": {"batch_input_shape": {"class_name": "__tuple__", "items": [null, 1]}, "dtype": "float32", "sparse": false, "ragged": false, "name": "input_3"}, "name": "input_3", "inbound_nodes": []}, {"class_name": "InputLayer", "config": {"batch_input_shape": {"class_name": "__tuple__", "items": [null, 1]}, "dtype": "float32", "sparse": false, "ragged": false, "name": "input_4"}, "name": "input_4", "inbound_nodes": []}, {"class_name": "Dense", "config": {"name": "dense_7", "trainable": true, "dtype": "float32", "units": 64, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}}, "bias_initializer": {"class_name": "Zeros", "config": {}}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_7", "inbound_nodes": [[["input_2", 0, 0, {}]]]}, {"class_name": "Dense", "config": {"name": "dense_8", "trainable": true, "dtype": "float32", "units": 32, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}}, "bias_initializer": {"class_name": "Zeros", "config": {}}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_8", "inbound_nodes": [[["input_3", 0, 0, {}]]]}, {"class_name": "Dense", "config": {"name": "dense_9", "trainable": true, "dtype": "float32", "units": 32, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}}, "bias_initializer": {"class_name": "Zeros", "config": {}}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_9", "inbound_nodes": [[["input_4", 0, 0, {}]]]}, {"class_name": "Concatenate", "config": {"name": "concatenate", "trainable": true, "dtype": "float32", "axis": -1}, "name": "concatenate", "inbound_nodes": [[["dense_7", 0, 0, {}], ["dense_8", 0, 0, {}], ["dense_9", 0, 0, {}]]]}, {"class_name": "Dense", "config": {"name": "dense_10", "trainable": true, "dtype": "float32", "units": 256, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}}, "bias_initializer": {"class_name": "Zeros", "config": {}}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_10", "inbound_nodes": [[["concatenate", 0, 0, {}]]]}, {"class_name": "Dense", "config": {"name": "dense_11", "trainable": true, "dtype": "float32", "units": 256, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}}, "bias_initializer": {"class_name": "Zeros", "config": {}}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_11", "inbound_nodes": [[["dense_10", 0, 0, {}]]]}, {"class_name": "Dense", "config": {"name": "dense_12", "trainable": true, "dtype": "float32", "units": 1, "activation": "linear", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}}, "bias_initializer": {"class_name": "Zeros", "config": {}}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_12", "inbound_nodes": [[["dense_11", 0, 0, {}]]]}], "input_layers": [["input_2", 0, 0], ["input_3", 0, 0], ["input_4", 0, 0]], "output_layers": [["dense_12", 0, 0]]}, "shared_object_id": 22, "input_spec": [{"class_name": "InputSpec", "config": {"dtype": null, "shape": {"class_name": "__tuple__", "items": [null, 8]}, "ndim": 2, "max_ndim": null, "min_ndim": null, "axes": {}}}, {"class_name": "InputSpec", "config": {"dtype": null, "shape": {"class_name": "__tuple__", "items": [null, 1]}, "ndim": 2, "max_ndim": null, "min_ndim": null, "axes": {}}}, {"class_name": "InputSpec", "config": {"dtype": null, "shape": {"class_name": "__tuple__", "items": [null, 1]}, "ndim": 2, "max_ndim": null, "min_ndim": null, "axes": {}}}], "build_input_shape": [{"class_name": "TensorShape", "items": [null, 8]}, {"class_name": "TensorShape", "items": [null, 1]}, {"class_name": "TensorShape", "items": [null, 1]}], "is_graph_network": true, "full_save_spec": {"class_name": "__tuple__", "items": [[[{"class_name": "TypeSpec", "type_spec": "tf.TensorSpec", "serialized": [{"class_name": "TensorShape", "items": [null, 8]}, "float32", "input_2"]}, {"class_name": "TypeSpec", "type_spec": "tf.TensorSpec", "serialized": [{"class_name": "TensorShape", "items": [null, 1]}, "float32", "input_3"]}, {"class_name": "TypeSpec", "type_spec": "tf.TensorSpec", "serialized": [{"class_name": "TensorShape", "items": [null, 1]}, "float32", "input_4"]}]], {}]}, "save_spec": [{"class_name": "TypeSpec", "type_spec": "tf.TensorSpec", "serialized": [{"class_name": "TensorShape", "items": [null, 8]}, "float32", "input_2"]}, {"class_name": "TypeSpec", "type_spec": "tf.TensorSpec", "serialized": [{"class_name": "TensorShape", "items": [null, 1]}, "float32", "input_3"]}, {"class_name": "TypeSpec", "type_spec": "tf.TensorSpec", "serialized": [{"class_name": "TensorShape", "items": [null, 1]}, "float32", "input_4"]}], "keras_version": "2.11.0", "backend": "tensorflow", "model_config": {"class_name": "Functional", "config": {"name": "model", "layers": [{"class_name": "InputLayer", "config": {"batch_input_shape": {"class_name": "__tuple__", "items": [null, 8]}, "dtype": "float32", "sparse": false, "ragged": false, "name": "input_2"}, "name": "input_2", "inbound_nodes": [], "shared_object_id": 0}, {"class_name": "InputLayer", "config": {"batch_input_shape": {"class_name": "__tuple__", "items": [null, 1]}, "dtype": "float32", "sparse": false, "ragged": false, "name": "input_3"}, "name": "input_3", "inbound_nodes": [], "shared_object_id": 1}, {"class_name": "InputLayer", "config": {"batch_input_shape": {"class_name": "__tuple__", "items": [null, 1]}, "dtype": "float32", "sparse": false, "ragged": false, "name": "input_4"}, "name": "input_4", "inbound_nodes": [], "shared_object_id": 2}, {"class_name": "Dense", "config": {"name": "dense_7", "trainable": true, "dtype": "float32", "units": 64, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 3}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 4}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_7", "inbound_nodes": [[["input_2", 0, 0, {}]]], "shared_object_id": 5}, {"class_name": "Dense", "config": {"name": "dense_8", "trainable": true, "dtype": "float32", "units": 32, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 6}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 7}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_8", "inbound_nodes": [[["input_3", 0, 0, {}]]], "shared_object_id": 8}, {"class_name": "Dense", "config": {"name": "dense_9", "trainable": true, "dtype": "float32", "units": 32, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 9}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 10}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_9", "inbound_nodes": [[["input_4", 0, 0, {}]]], "shared_object_id": 11}, {"class_name": "Concatenate", "config": {"name": "concatenate", "trainable": true, "dtype": "float32", "axis": -1}, "name": "concatenate", "inbound_nodes": [[["dense_7", 0, 0, {}], ["dense_8", 0, 0, {}], ["dense_9", 0, 0, {}]]], "shared_object_id": 12}, {"class_name": "Dense", "config": {"name": "dense_10", "trainable": true, "dtype": "float32", "units": 256, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 13}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 14}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_10", "inbound_nodes": [[["concatenate", 0, 0, {}]]], "shared_object_id": 15}, {"class_name": "Dense", "config": {"name": "dense_11", "trainable": true, "dtype": "float32", "units": 256, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 16}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 17}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_11", "inbound_nodes": [[["dense_10", 0, 0, {}]]], "shared_object_id": 18}, {"class_name": "Dense", "config": {"name": "dense_12", "trainable": true, "dtype": "float32", "units": 1, "activation": "linear", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 19}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 20}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_12", "inbound_nodes": [[["dense_11", 0, 0, {}]]], "shared_object_id": 21}], "input_layers": [["input_2", 0, 0], ["input_3", 0, 0], ["input_4", 0, 0]], "output_layers": [["dense_12", 0, 0]]}}, "training_config": {"loss": "mse", "metrics": null, "weighted_metrics": null, "loss_weights": null, "optimizer_config": {"class_name": "Custom>Adam", "config": {"name": "Adam", "weight_decay": null, "clipnorm": null, "global_clipnorm": null, "clipvalue": null, "use_ema": false, "ema_momentum": 0.99, "ema_overwrite_frequency": null, "jit_compile": true, "is_legacy_optimizer": false, "learning_rate": 0.004999999888241291, "beta_1": 0.9, "beta_2": 0.999, "epsilon": 1e-07, "amsgrad": false}}}}2 + root.layer-0"_tf_keras_input_layer*{"class_name": "InputLayer", "name": "input_2", "dtype": "float32", "sparse": false, "ragged": false, "batch_input_shape": {"class_name": "__tuple__", "items": [null, 8]}, "config": {"batch_input_shape": {"class_name": "__tuple__", "items": [null, 8]}, "dtype": "float32", "sparse": false, "ragged": false, "name": "input_2"}}2 + root.layer-1"_tf_keras_input_layer*{"class_name": "InputLayer", "name": "input_3", "dtype": "float32", "sparse": false, "ragged": false, "batch_input_shape": {"class_name": "__tuple__", "items": [null, 1]}, "config": {"batch_input_shape": {"class_name": "__tuple__", "items": [null, 1]}, "dtype": "float32", "sparse": false, "ragged": false, "name": "input_3"}}2 + root.layer-2"_tf_keras_input_layer*{"class_name": "InputLayer", "name": "input_4", "dtype": "float32", "sparse": false, "ragged": false, "batch_input_shape": {"class_name": "__tuple__", "items": [null, 1]}, "config": {"batch_input_shape": {"class_name": "__tuple__", "items": [null, 1]}, "dtype": "float32", "sparse": false, "ragged": false, "name": "input_4"}}2 +root.layer_with_weights-0"_tf_keras_layer*{"name": "dense_7", "trainable": true, "expects_training_arg": false, "dtype": "float32", "batch_input_shape": null, "stateful": false, "must_restore_from_config": false, "preserve_input_structure_in_config": false, "autocast": true, "class_name": "Dense", "config": {"name": "dense_7", "trainable": true, "dtype": "float32", "units": 64, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 3}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 4}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "inbound_nodes": [[["input_2", 0, 0, {}]]], "shared_object_id": 5, "input_spec": {"class_name": "InputSpec", "config": {"dtype": null, "shape": null, "ndim": null, "max_ndim": null, "min_ndim": 2, "axes": {"-1": 8}}, "shared_object_id": 26}, "build_input_shape": {"class_name": "TensorShape", "items": [null, 8]}}2 +root.layer_with_weights-1"_tf_keras_layer*{"name": "dense_8", "trainable": true, "expects_training_arg": false, "dtype": "float32", "batch_input_shape": null, "stateful": false, "must_restore_from_config": false, "preserve_input_structure_in_config": false, "autocast": true, "class_name": "Dense", "config": {"name": "dense_8", "trainable": true, "dtype": "float32", "units": 32, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 6}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 7}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "inbound_nodes": [[["input_3", 0, 0, {}]]], "shared_object_id": 8, "input_spec": {"class_name": "InputSpec", "config": {"dtype": null, "shape": null, "ndim": null, "max_ndim": null, "min_ndim": 2, "axes": {"-1": 1}}, "shared_object_id": 27}, "build_input_shape": {"class_name": "TensorShape", "items": [null, 1]}}2 +root.layer_with_weights-2"_tf_keras_layer*{"name": "dense_9", "trainable": true, "expects_training_arg": false, "dtype": "float32", "batch_input_shape": null, "stateful": false, "must_restore_from_config": false, "preserve_input_structure_in_config": false, "autocast": true, "class_name": "Dense", "config": {"name": "dense_9", "trainable": true, "dtype": "float32", "units": 32, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 9}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 10}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "inbound_nodes": [[["input_4", 0, 0, {}]]], "shared_object_id": 11, "input_spec": {"class_name": "InputSpec", "config": {"dtype": null, "shape": null, "ndim": null, "max_ndim": null, "min_ndim": 2, "axes": {"-1": 1}}, "shared_object_id": 28}, "build_input_shape": {"class_name": "TensorShape", "items": [null, 1]}}2 + root.layer-6"_tf_keras_layer*{"name": "concatenate", "trainable": true, "expects_training_arg": false, "dtype": "float32", "batch_input_shape": null, "stateful": false, "must_restore_from_config": false, "preserve_input_structure_in_config": false, "autocast": true, "class_name": "Concatenate", "config": {"name": "concatenate", "trainable": true, "dtype": "float32", "axis": -1}, "inbound_nodes": [[["dense_7", 0, 0, {}], ["dense_8", 0, 0, {}], ["dense_9", 0, 0, {}]]], "shared_object_id": 12, "build_input_shape": [{"class_name": "TensorShape", "items": [null, 64]}, {"class_name": "TensorShape", "items": [null, 32]}, {"class_name": "TensorShape", "items": [null, 32]}]}2 +root.layer_with_weights-3"_tf_keras_layer*{"name": "dense_10", "trainable": true, "expects_training_arg": false, "dtype": "float32", "batch_input_shape": null, "stateful": false, "must_restore_from_config": false, "preserve_input_structure_in_config": false, "autocast": true, "class_name": "Dense", "config": {"name": "dense_10", "trainable": true, "dtype": "float32", "units": 256, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 13}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 14}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "inbound_nodes": [[["concatenate", 0, 0, {}]]], "shared_object_id": 15, "input_spec": {"class_name": "InputSpec", "config": {"dtype": null, "shape": null, "ndim": null, "max_ndim": null, "min_ndim": 2, "axes": {"-1": 128}}, "shared_object_id": 29}, "build_input_shape": {"class_name": "TensorShape", "items": [null, 128]}}2 + root.layer_with_weights-4"_tf_keras_layer*{"name": "dense_11", "trainable": true, "expects_training_arg": false, "dtype": "float32", "batch_input_shape": null, "stateful": false, "must_restore_from_config": false, "preserve_input_structure_in_config": false, "autocast": true, "class_name": "Dense", "config": {"name": "dense_11", "trainable": true, "dtype": "float32", "units": 256, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 16}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 17}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "inbound_nodes": [[["dense_10", 0, 0, {}]]], "shared_object_id": 18, "input_spec": {"class_name": "InputSpec", "config": {"dtype": null, "shape": null, "ndim": null, "max_ndim": null, "min_ndim": 2, "axes": {"-1": 256}}, "shared_object_id": 30}, "build_input_shape": {"class_name": "TensorShape", "items": [null, 256]}}2 + +root.layer_with_weights-5"_tf_keras_layer*{"name": "dense_12", "trainable": true, "expects_training_arg": false, "dtype": "float32", "batch_input_shape": null, "stateful": false, "must_restore_from_config": false, "preserve_input_structure_in_config": false, "autocast": true, "class_name": "Dense", "config": {"name": "dense_12", "trainable": true, "dtype": "float32", "units": 1, "activation": "linear", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 19}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 20}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "inbound_nodes": [[["dense_11", 0, 0, {}]]], "shared_object_id": 21, "input_spec": {"class_name": "InputSpec", "config": {"dtype": null, "shape": null, "ndim": null, "max_ndim": null, "min_ndim": 2, "axes": {"-1": 256}}, "shared_object_id": 31}, "build_input_shape": {"class_name": "TensorShape", "items": [null, 256]}}2 +root.keras_api.metrics.0"_tf_keras_metric*{"class_name": "Mean", "name": "loss", "dtype": "float32", "config": {"name": "loss", "dtype": "float32"}, "shared_object_id": 32}2 \ No newline at end of file diff --git a/behavior_metrics/models/gazebo/rl_models/ddpg/superfast-20231118-220658_IMPROVED_C-simple_S-sp5_A-continuous_MR-2025_E-3797/CRITIC/saved_model.pb b/behavior_metrics/models/gazebo/rl_models/ddpg/superfast-20231118-220658_IMPROVED_C-simple_S-sp5_A-continuous_MR-2025_E-3797/CRITIC/saved_model.pb new file mode 100644 index 00000000..6d8c0983 Binary files /dev/null and b/behavior_metrics/models/gazebo/rl_models/ddpg/superfast-20231118-220658_IMPROVED_C-simple_S-sp5_A-continuous_MR-2025_E-3797/CRITIC/saved_model.pb differ diff --git a/behavior_metrics/models/gazebo/rl_models/ddpg/superfast-20231118-220658_IMPROVED_C-simple_S-sp5_A-continuous_MR-2025_E-3797/CRITIC/variables/variables.data-00000-of-00001 b/behavior_metrics/models/gazebo/rl_models/ddpg/superfast-20231118-220658_IMPROVED_C-simple_S-sp5_A-continuous_MR-2025_E-3797/CRITIC/variables/variables.data-00000-of-00001 new file mode 100644 index 00000000..d1faf120 Binary files /dev/null and b/behavior_metrics/models/gazebo/rl_models/ddpg/superfast-20231118-220658_IMPROVED_C-simple_S-sp5_A-continuous_MR-2025_E-3797/CRITIC/variables/variables.data-00000-of-00001 differ diff --git a/behavior_metrics/models/gazebo/rl_models/ddpg/superfast-20231118-220658_IMPROVED_C-simple_S-sp5_A-continuous_MR-2025_E-3797/CRITIC/variables/variables.index b/behavior_metrics/models/gazebo/rl_models/ddpg/superfast-20231118-220658_IMPROVED_C-simple_S-sp5_A-continuous_MR-2025_E-3797/CRITIC/variables/variables.index new file mode 100644 index 00000000..f1d2a037 Binary files /dev/null and b/behavior_metrics/models/gazebo/rl_models/ddpg/superfast-20231118-220658_IMPROVED_C-simple_S-sp5_A-continuous_MR-2025_E-3797/CRITIC/variables/variables.index differ diff --git a/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max2951_Epoch267_inTime20231220-121204.model/fingerprint.pb b/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max2951_Epoch267_inTime20231220-121204.model/fingerprint.pb new file mode 100644 index 00000000..b23c05dc Binary files /dev/null and b/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max2951_Epoch267_inTime20231220-121204.model/fingerprint.pb differ diff --git a/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max2951_Epoch267_inTime20231220-121204.model/keras_metadata.pb b/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max2951_Epoch267_inTime20231220-121204.model/keras_metadata.pb new file mode 100644 index 00000000..972cd011 --- /dev/null +++ b/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max2951_Epoch267_inTime20231220-121204.model/keras_metadata.pb @@ -0,0 +1,7 @@ + +*root"_tf_keras_network*){"name": "model", "trainable": true, "expects_training_arg": true, "dtype": "float32", "batch_input_shape": null, "must_restore_from_config": false, "preserve_input_structure_in_config": false, "autocast": false, "class_name": "Functional", "config": {"name": "model", "layers": [{"class_name": "InputLayer", "config": {"batch_input_shape": {"class_name": "__tuple__", "items": [null, 10]}, "dtype": "float32", "sparse": false, "ragged": false, "name": "input_1"}, "name": "input_1", "inbound_nodes": []}, {"class_name": "Dense", "config": {"name": "dense", "trainable": true, "dtype": "float32", "units": 16, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}}, "bias_initializer": {"class_name": "Zeros", "config": {}}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense", "inbound_nodes": [[["input_1", 0, 0, {}]]]}, {"class_name": "Dense", "config": {"name": "dense_1", "trainable": true, "dtype": "float32", "units": 16, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}}, "bias_initializer": {"class_name": "Zeros", "config": {}}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_1", "inbound_nodes": [[["dense", 0, 0, {}]]]}, {"class_name": "Dense", "config": {"name": "dense_2", "trainable": true, "dtype": "float32", "units": 9, "activation": "linear", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}}, "bias_initializer": {"class_name": "Zeros", "config": {}}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_2", "inbound_nodes": [[["dense_1", 0, 0, {}]]]}], "input_layers": [["input_1", 0, 0]], "output_layers": [["dense_2", 0, 0]]}, "shared_object_id": 10, "input_spec": [{"class_name": "InputSpec", "config": {"dtype": null, "shape": {"class_name": "__tuple__", "items": [null, 10]}, "ndim": 2, "max_ndim": null, "min_ndim": null, "axes": {}}}], "build_input_shape": {"class_name": "TensorShape", "items": [null, 10]}, "is_graph_network": true, "full_save_spec": {"class_name": "__tuple__", "items": [[{"class_name": "TypeSpec", "type_spec": "tf.TensorSpec", "serialized": [{"class_name": "TensorShape", "items": [null, 10]}, "float32", "input_1"]}], {}]}, "save_spec": {"class_name": "TypeSpec", "type_spec": "tf.TensorSpec", "serialized": [{"class_name": "TensorShape", "items": [null, 10]}, "float32", "input_1"]}, "keras_version": "2.11.0", "backend": "tensorflow", "model_config": {"class_name": "Functional", "config": {"name": "model", "layers": [{"class_name": "InputLayer", "config": {"batch_input_shape": {"class_name": "__tuple__", "items": [null, 10]}, "dtype": "float32", "sparse": false, "ragged": false, "name": "input_1"}, "name": "input_1", "inbound_nodes": [], "shared_object_id": 0}, {"class_name": "Dense", "config": {"name": "dense", "trainable": true, "dtype": "float32", "units": 16, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 1}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 2}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense", "inbound_nodes": [[["input_1", 0, 0, {}]]], "shared_object_id": 3}, {"class_name": "Dense", "config": {"name": "dense_1", "trainable": true, "dtype": "float32", "units": 16, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 4}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 5}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_1", "inbound_nodes": [[["dense", 0, 0, {}]]], "shared_object_id": 6}, {"class_name": "Dense", "config": {"name": "dense_2", "trainable": true, "dtype": "float32", "units": 9, "activation": "linear", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 7}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 8}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_2", "inbound_nodes": [[["dense_1", 0, 0, {}]]], "shared_object_id": 9}], "input_layers": [["input_1", 0, 0]], "output_layers": [["dense_2", 0, 0]]}}, "training_config": {"loss": "mean_squared_error", "metrics": null, "weighted_metrics": null, "loss_weights": null, "optimizer_config": {"class_name": "Custom>Adam", "config": {"name": "Adam", "weight_decay": null, "clipnorm": null, "global_clipnorm": null, "clipvalue": null, "use_ema": false, "ema_momentum": 0.99, "ema_overwrite_frequency": null, "jit_compile": true, "is_legacy_optimizer": false, "learning_rate": 0.004999999888241291, "beta_1": 0.9, "beta_2": 0.999, "epsilon": 1e-07, "amsgrad": false}}}}2 + root.layer-0"_tf_keras_input_layer*{"class_name": "InputLayer", "name": "input_1", "dtype": "float32", "sparse": false, "ragged": false, "batch_input_shape": {"class_name": "__tuple__", "items": [null, 10]}, "config": {"batch_input_shape": {"class_name": "__tuple__", "items": [null, 10]}, "dtype": "float32", "sparse": false, "ragged": false, "name": "input_1"}}2 +root.layer_with_weights-0"_tf_keras_layer*{"name": "dense", "trainable": true, "expects_training_arg": false, "dtype": "float32", "batch_input_shape": null, "stateful": false, "must_restore_from_config": false, "preserve_input_structure_in_config": false, "autocast": true, "class_name": "Dense", "config": {"name": "dense", "trainable": true, "dtype": "float32", "units": 16, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 1}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 2}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "inbound_nodes": [[["input_1", 0, 0, {}]]], "shared_object_id": 3, "input_spec": {"class_name": "InputSpec", "config": {"dtype": null, "shape": null, "ndim": null, "max_ndim": null, "min_ndim": 2, "axes": {"-1": 10}}, "shared_object_id": 12}, "build_input_shape": {"class_name": "TensorShape", "items": [null, 10]}}2 +root.layer_with_weights-1"_tf_keras_layer*{"name": "dense_1", "trainable": true, "expects_training_arg": false, "dtype": "float32", "batch_input_shape": null, "stateful": false, "must_restore_from_config": false, "preserve_input_structure_in_config": false, "autocast": true, "class_name": "Dense", "config": {"name": "dense_1", "trainable": true, "dtype": "float32", "units": 16, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 4}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 5}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "inbound_nodes": [[["dense", 0, 0, {}]]], "shared_object_id": 6, "input_spec": {"class_name": "InputSpec", "config": {"dtype": null, "shape": null, "ndim": null, "max_ndim": null, "min_ndim": 2, "axes": {"-1": 16}}, "shared_object_id": 13}, "build_input_shape": {"class_name": "TensorShape", "items": [null, 16]}}2 +root.layer_with_weights-2"_tf_keras_layer*{"name": "dense_2", "trainable": true, "expects_training_arg": false, "dtype": "float32", "batch_input_shape": null, "stateful": false, "must_restore_from_config": false, "preserve_input_structure_in_config": false, "autocast": true, "class_name": "Dense", "config": {"name": "dense_2", "trainable": true, "dtype": "float32", "units": 9, "activation": "linear", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 7}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 8}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "inbound_nodes": [[["dense_1", 0, 0, {}]]], "shared_object_id": 9, "input_spec": {"class_name": "InputSpec", "config": {"dtype": null, "shape": null, "ndim": null, "max_ndim": null, "min_ndim": 2, "axes": {"-1": 16}}, "shared_object_id": 14}, "build_input_shape": {"class_name": "TensorShape", "items": [null, 16]}}2 +Uroot.keras_api.metrics.0"_tf_keras_metric*{"class_name": "Mean", "name": "loss", "dtype": "float32", "config": {"name": "loss", "dtype": "float32"}, "shared_object_id": 15}2 \ No newline at end of file diff --git a/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max5334_Epoch596_inTime20230310-223500.model/saved_model.pb b/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max2951_Epoch267_inTime20231220-121204.model/saved_model.pb similarity index 82% rename from behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max5334_Epoch596_inTime20230310-223500.model/saved_model.pb rename to behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max2951_Epoch267_inTime20231220-121204.model/saved_model.pb index 862c7551..d3a102e0 100644 Binary files a/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max5334_Epoch596_inTime20230310-223500.model/saved_model.pb and b/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max2951_Epoch267_inTime20231220-121204.model/saved_model.pb differ diff --git a/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max2951_Epoch267_inTime20231220-121204.model/variables/variables.data-00000-of-00001 b/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max2951_Epoch267_inTime20231220-121204.model/variables/variables.data-00000-of-00001 new file mode 100644 index 00000000..cfc98aa2 Binary files /dev/null and b/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max2951_Epoch267_inTime20231220-121204.model/variables/variables.data-00000-of-00001 differ diff --git a/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max2951_Epoch267_inTime20231220-121204.model/variables/variables.index b/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max2951_Epoch267_inTime20231220-121204.model/variables/variables.index new file mode 100644 index 00000000..2b94c22a Binary files /dev/null and b/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max2951_Epoch267_inTime20231220-121204.model/variables/variables.index differ diff --git a/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max5334_Epoch596_inTime20230310-223500.model/fingerprint.pb b/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max5334_Epoch596_inTime20230310-223500.model/fingerprint.pb deleted file mode 100644 index 6f752402..00000000 Binary files a/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max5334_Epoch596_inTime20230310-223500.model/fingerprint.pb and /dev/null differ diff --git a/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max5334_Epoch596_inTime20230310-223500.model/keras_metadata.pb b/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max5334_Epoch596_inTime20230310-223500.model/keras_metadata.pb deleted file mode 100644 index 02a04aca..00000000 --- a/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max5334_Epoch596_inTime20230310-223500.model/keras_metadata.pb +++ /dev/null @@ -1,7 +0,0 @@ - -*root"_tf_keras_network*){"name": "model", "trainable": true, "expects_training_arg": true, "dtype": "float32", "batch_input_shape": null, "must_restore_from_config": false, "preserve_input_structure_in_config": false, "autocast": false, "class_name": "Functional", "config": {"name": "model", "layers": [{"class_name": "InputLayer", "config": {"batch_input_shape": {"class_name": "__tuple__", "items": [null, 1]}, "dtype": "float32", "sparse": false, "ragged": false, "name": "input_1"}, "name": "input_1", "inbound_nodes": []}, {"class_name": "Dense", "config": {"name": "dense", "trainable": true, "dtype": "float32", "units": 16, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}}, "bias_initializer": {"class_name": "Zeros", "config": {}}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense", "inbound_nodes": [[["input_1", 0, 0, {}]]]}, {"class_name": "Dense", "config": {"name": "dense_1", "trainable": true, "dtype": "float32", "units": 16, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}}, "bias_initializer": {"class_name": "Zeros", "config": {}}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_1", "inbound_nodes": [[["dense", 0, 0, {}]]]}, {"class_name": "Dense", "config": {"name": "dense_2", "trainable": true, "dtype": "float32", "units": 3, "activation": "linear", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}}, "bias_initializer": {"class_name": "Zeros", "config": {}}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_2", "inbound_nodes": [[["dense_1", 0, 0, {}]]]}], "input_layers": [["input_1", 0, 0]], "output_layers": [["dense_2", 0, 0]]}, "shared_object_id": 10, "input_spec": [{"class_name": "InputSpec", "config": {"dtype": null, "shape": {"class_name": "__tuple__", "items": [null, 1]}, "ndim": 2, "max_ndim": null, "min_ndim": null, "axes": {}}}], "build_input_shape": {"class_name": "TensorShape", "items": [null, 1]}, "is_graph_network": true, "full_save_spec": {"class_name": "__tuple__", "items": [[{"class_name": "TypeSpec", "type_spec": "tf.TensorSpec", "serialized": [{"class_name": "TensorShape", "items": [null, 1]}, "float32", "input_1"]}], {}]}, "save_spec": {"class_name": "TypeSpec", "type_spec": "tf.TensorSpec", "serialized": [{"class_name": "TensorShape", "items": [null, 1]}, "float32", "input_1"]}, "keras_version": "2.11.0", "backend": "tensorflow", "model_config": {"class_name": "Functional", "config": {"name": "model", "layers": [{"class_name": "InputLayer", "config": {"batch_input_shape": {"class_name": "__tuple__", "items": [null, 1]}, "dtype": "float32", "sparse": false, "ragged": false, "name": "input_1"}, "name": "input_1", "inbound_nodes": [], "shared_object_id": 0}, {"class_name": "Dense", "config": {"name": "dense", "trainable": true, "dtype": "float32", "units": 16, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 1}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 2}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense", "inbound_nodes": [[["input_1", 0, 0, {}]]], "shared_object_id": 3}, {"class_name": "Dense", "config": {"name": "dense_1", "trainable": true, "dtype": "float32", "units": 16, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 4}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 5}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_1", "inbound_nodes": [[["dense", 0, 0, {}]]], "shared_object_id": 6}, {"class_name": "Dense", "config": {"name": "dense_2", "trainable": true, "dtype": "float32", "units": 3, "activation": "linear", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 7}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 8}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_2", "inbound_nodes": [[["dense_1", 0, 0, {}]]], "shared_object_id": 9}], "input_layers": [["input_1", 0, 0]], "output_layers": [["dense_2", 0, 0]]}}, "training_config": {"loss": "mean_squared_error", "metrics": null, "weighted_metrics": null, "loss_weights": null, "optimizer_config": {"class_name": "Custom>Adam", "config": {"name": "Adam", "weight_decay": null, "clipnorm": null, "global_clipnorm": null, "clipvalue": null, "use_ema": false, "ema_momentum": 0.99, "ema_overwrite_frequency": null, "jit_compile": true, "is_legacy_optimizer": false, "learning_rate": 0.004999999888241291, "beta_1": 0.9, "beta_2": 0.999, "epsilon": 1e-07, "amsgrad": false}}}}2 - root.layer-0"_tf_keras_input_layer*{"class_name": "InputLayer", "name": "input_1", "dtype": "float32", "sparse": false, "ragged": false, "batch_input_shape": {"class_name": "__tuple__", "items": [null, 1]}, "config": {"batch_input_shape": {"class_name": "__tuple__", "items": [null, 1]}, "dtype": "float32", "sparse": false, "ragged": false, "name": "input_1"}}2 -root.layer_with_weights-0"_tf_keras_layer*{"name": "dense", "trainable": true, "expects_training_arg": false, "dtype": "float32", "batch_input_shape": null, "stateful": false, "must_restore_from_config": false, "preserve_input_structure_in_config": false, "autocast": true, "class_name": "Dense", "config": {"name": "dense", "trainable": true, "dtype": "float32", "units": 16, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 1}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 2}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "inbound_nodes": [[["input_1", 0, 0, {}]]], "shared_object_id": 3, "input_spec": {"class_name": "InputSpec", "config": {"dtype": null, "shape": null, "ndim": null, "max_ndim": null, "min_ndim": 2, "axes": {"-1": 1}}, "shared_object_id": 12}, "build_input_shape": {"class_name": "TensorShape", "items": [null, 1]}}2 -root.layer_with_weights-1"_tf_keras_layer*{"name": "dense_1", "trainable": true, "expects_training_arg": false, "dtype": "float32", "batch_input_shape": null, "stateful": false, "must_restore_from_config": false, "preserve_input_structure_in_config": false, "autocast": true, "class_name": "Dense", "config": {"name": "dense_1", "trainable": true, "dtype": "float32", "units": 16, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 4}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 5}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "inbound_nodes": [[["dense", 0, 0, {}]]], "shared_object_id": 6, "input_spec": {"class_name": "InputSpec", "config": {"dtype": null, "shape": null, "ndim": null, "max_ndim": null, "min_ndim": 2, "axes": {"-1": 16}}, "shared_object_id": 13}, "build_input_shape": {"class_name": "TensorShape", "items": [null, 16]}}2 -root.layer_with_weights-2"_tf_keras_layer*{"name": "dense_2", "trainable": true, "expects_training_arg": false, "dtype": "float32", "batch_input_shape": null, "stateful": false, "must_restore_from_config": false, "preserve_input_structure_in_config": false, "autocast": true, "class_name": "Dense", "config": {"name": "dense_2", "trainable": true, "dtype": "float32", "units": 3, "activation": "linear", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 7}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 8}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "inbound_nodes": [[["dense_1", 0, 0, {}]]], "shared_object_id": 9, "input_spec": {"class_name": "InputSpec", "config": {"dtype": null, "shape": null, "ndim": null, "max_ndim": null, "min_ndim": 2, "axes": {"-1": 16}}, "shared_object_id": 14}, "build_input_shape": {"class_name": "TensorShape", "items": [null, 16]}}2 -Uroot.keras_api.metrics.0"_tf_keras_metric*{"class_name": "Mean", "name": "loss", "dtype": "float32", "config": {"name": "loss", "dtype": "float32"}, "shared_object_id": 15}2 \ No newline at end of file diff --git a/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max5334_Epoch596_inTime20230310-223500.model/variables/variables.data-00000-of-00001 b/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max5334_Epoch596_inTime20230310-223500.model/variables/variables.data-00000-of-00001 deleted file mode 100644 index 56445ddf..00000000 Binary files a/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max5334_Epoch596_inTime20230310-223500.model/variables/variables.data-00000-of-00001 and /dev/null differ diff --git a/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max5334_Epoch596_inTime20230310-223500.model/variables/variables.index b/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max5334_Epoch596_inTime20230310-223500.model/variables/variables.index deleted file mode 100644 index 728d9c18..00000000 Binary files a/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max5334_Epoch596_inTime20230310-223500.model/variables/variables.index and /dev/null differ diff --git a/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max569_Epoch1455_inTime20230413-103523.model/fingerprint.pb b/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max569_Epoch1455_inTime20230413-103523.model/fingerprint.pb deleted file mode 100644 index 902cdbea..00000000 Binary files a/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max569_Epoch1455_inTime20230413-103523.model/fingerprint.pb and /dev/null differ diff --git a/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max569_Epoch1455_inTime20230413-103523.model/keras_metadata.pb b/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max569_Epoch1455_inTime20230413-103523.model/keras_metadata.pb deleted file mode 100644 index 34cd4e36..00000000 --- a/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max569_Epoch1455_inTime20230413-103523.model/keras_metadata.pb +++ /dev/null @@ -1,7 +0,0 @@ - -)root"_tf_keras_network*){"name": "model", "trainable": true, "expects_training_arg": true, "dtype": "float32", "batch_input_shape": null, "must_restore_from_config": false, "preserve_input_structure_in_config": false, "autocast": false, "class_name": "Functional", "config": {"name": "model", "layers": [{"class_name": "InputLayer", "config": {"batch_input_shape": {"class_name": "__tuple__", "items": [null, 1]}, "dtype": "float32", "sparse": false, "ragged": false, "name": "input_1"}, "name": "input_1", "inbound_nodes": []}, {"class_name": "Dense", "config": {"name": "dense", "trainable": true, "dtype": "float32", "units": 16, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}}, "bias_initializer": {"class_name": "Zeros", "config": {}}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense", "inbound_nodes": [[["input_1", 0, 0, {}]]]}, {"class_name": "Dense", "config": {"name": "dense_1", "trainable": true, "dtype": "float32", "units": 16, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}}, "bias_initializer": {"class_name": "Zeros", "config": {}}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_1", "inbound_nodes": [[["dense", 0, 0, {}]]]}, {"class_name": "Dense", "config": {"name": "dense_2", "trainable": true, "dtype": "float32", "units": 3, "activation": "linear", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}}, "bias_initializer": {"class_name": "Zeros", "config": {}}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_2", "inbound_nodes": [[["dense_1", 0, 0, {}]]]}], "input_layers": [["input_1", 0, 0]], "output_layers": [["dense_2", 0, 0]]}, "shared_object_id": 10, "input_spec": [{"class_name": "InputSpec", "config": {"dtype": null, "shape": {"class_name": "__tuple__", "items": [null, 1]}, "ndim": 2, "max_ndim": null, "min_ndim": null, "axes": {}}}], "build_input_shape": {"class_name": "TensorShape", "items": [null, 1]}, "is_graph_network": true, "full_save_spec": {"class_name": "__tuple__", "items": [[{"class_name": "TypeSpec", "type_spec": "tf.TensorSpec", "serialized": [{"class_name": "TensorShape", "items": [null, 1]}, "float32", "input_1"]}], {}]}, "save_spec": {"class_name": "TypeSpec", "type_spec": "tf.TensorSpec", "serialized": [{"class_name": "TensorShape", "items": [null, 1]}, "float32", "input_1"]}, "keras_version": "2.11.0", "backend": "tensorflow", "model_config": {"class_name": "Functional", "config": {"name": "model", "layers": [{"class_name": "InputLayer", "config": {"batch_input_shape": {"class_name": "__tuple__", "items": [null, 1]}, "dtype": "float32", "sparse": false, "ragged": false, "name": "input_1"}, "name": "input_1", "inbound_nodes": [], "shared_object_id": 0}, {"class_name": "Dense", "config": {"name": "dense", "trainable": true, "dtype": "float32", "units": 16, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 1}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 2}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense", "inbound_nodes": [[["input_1", 0, 0, {}]]], "shared_object_id": 3}, {"class_name": "Dense", "config": {"name": "dense_1", "trainable": true, "dtype": "float32", "units": 16, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 4}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 5}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_1", "inbound_nodes": [[["dense", 0, 0, {}]]], "shared_object_id": 6}, {"class_name": "Dense", "config": {"name": "dense_2", "trainable": true, "dtype": "float32", "units": 3, "activation": "linear", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 7}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 8}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_2", "inbound_nodes": [[["dense_1", 0, 0, {}]]], "shared_object_id": 9}], "input_layers": [["input_1", 0, 0]], "output_layers": [["dense_2", 0, 0]]}}, "training_config": {"loss": "mse", "metrics": null, "weighted_metrics": null, "loss_weights": null, "optimizer_config": {"class_name": "Custom>Adam", "config": {"name": "Adam", "weight_decay": null, "clipnorm": null, "global_clipnorm": null, "clipvalue": null, "use_ema": false, "ema_momentum": 0.99, "ema_overwrite_frequency": null, "jit_compile": true, "is_legacy_optimizer": false, "learning_rate": 0.004999999888241291, "beta_1": 0.9, "beta_2": 0.999, "epsilon": 1e-07, "amsgrad": false}}}}2 - root.layer-0"_tf_keras_input_layer*{"class_name": "InputLayer", "name": "input_1", "dtype": "float32", "sparse": false, "ragged": false, "batch_input_shape": {"class_name": "__tuple__", "items": [null, 1]}, "config": {"batch_input_shape": {"class_name": "__tuple__", "items": [null, 1]}, "dtype": "float32", "sparse": false, "ragged": false, "name": "input_1"}}2 -root.layer_with_weights-0"_tf_keras_layer*{"name": "dense", "trainable": true, "expects_training_arg": false, "dtype": "float32", "batch_input_shape": null, "stateful": false, "must_restore_from_config": false, "preserve_input_structure_in_config": false, "autocast": true, "class_name": "Dense", "config": {"name": "dense", "trainable": true, "dtype": "float32", "units": 16, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 1}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 2}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "inbound_nodes": [[["input_1", 0, 0, {}]]], "shared_object_id": 3, "input_spec": {"class_name": "InputSpec", "config": {"dtype": null, "shape": null, "ndim": null, "max_ndim": null, "min_ndim": 2, "axes": {"-1": 1}}, "shared_object_id": 12}, "build_input_shape": {"class_name": "TensorShape", "items": [null, 1]}}2 -root.layer_with_weights-1"_tf_keras_layer*{"name": "dense_1", "trainable": true, "expects_training_arg": false, "dtype": "float32", "batch_input_shape": null, "stateful": false, "must_restore_from_config": false, "preserve_input_structure_in_config": false, "autocast": true, "class_name": "Dense", "config": {"name": "dense_1", "trainable": true, "dtype": "float32", "units": 16, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 4}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 5}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "inbound_nodes": [[["dense", 0, 0, {}]]], "shared_object_id": 6, "input_spec": {"class_name": "InputSpec", "config": {"dtype": null, "shape": null, "ndim": null, "max_ndim": null, "min_ndim": 2, "axes": {"-1": 16}}, "shared_object_id": 13}, "build_input_shape": {"class_name": "TensorShape", "items": [null, 16]}}2 -root.layer_with_weights-2"_tf_keras_layer*{"name": "dense_2", "trainable": true, "expects_training_arg": false, "dtype": "float32", "batch_input_shape": null, "stateful": false, "must_restore_from_config": false, "preserve_input_structure_in_config": false, "autocast": true, "class_name": "Dense", "config": {"name": "dense_2", "trainable": true, "dtype": "float32", "units": 3, "activation": "linear", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 7}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 8}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "inbound_nodes": [[["dense_1", 0, 0, {}]]], "shared_object_id": 9, "input_spec": {"class_name": "InputSpec", "config": {"dtype": null, "shape": null, "ndim": null, "max_ndim": null, "min_ndim": 2, "axes": {"-1": 16}}, "shared_object_id": 14}, "build_input_shape": {"class_name": "TensorShape", "items": [null, 16]}}2 -Proot.keras_api.metrics.0"_tf_keras_metric*{"class_name": "Mean", "name": "loss", "dtype": "float32", "config": {"name": "loss", "dtype": "float32"}, "shared_object_id": 15}2 \ No newline at end of file diff --git a/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max569_Epoch1455_inTime20230413-103523.model/saved_model.pb b/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max569_Epoch1455_inTime20230413-103523.model/saved_model.pb deleted file mode 100644 index 412f461c..00000000 Binary files a/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max569_Epoch1455_inTime20230413-103523.model/saved_model.pb and /dev/null differ diff --git a/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max569_Epoch1455_inTime20230413-103523.model/variables/variables.data-00000-of-00001 b/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max569_Epoch1455_inTime20230413-103523.model/variables/variables.data-00000-of-00001 deleted file mode 100644 index 7cfad826..00000000 Binary files a/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max569_Epoch1455_inTime20230413-103523.model/variables/variables.data-00000-of-00001 and /dev/null differ diff --git a/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max569_Epoch1455_inTime20230413-103523.model/variables/variables.index b/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max569_Epoch1455_inTime20230413-103523.model/variables/variables.index deleted file mode 100644 index b14faf61..00000000 Binary files a/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max569_Epoch1455_inTime20230413-103523.model/variables/variables.index and /dev/null differ diff --git a/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max5742_Epoch591_inTime20230217-100807.model/fingerprint.pb b/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max5742_Epoch591_inTime20230217-100807.model/fingerprint.pb deleted file mode 100644 index 77083c1c..00000000 Binary files a/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max5742_Epoch591_inTime20230217-100807.model/fingerprint.pb and /dev/null differ diff --git a/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max5742_Epoch591_inTime20230217-100807.model/keras_metadata.pb b/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max5742_Epoch591_inTime20230217-100807.model/keras_metadata.pb deleted file mode 100644 index 34cd4e36..00000000 --- a/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max5742_Epoch591_inTime20230217-100807.model/keras_metadata.pb +++ /dev/null @@ -1,7 +0,0 @@ - -)root"_tf_keras_network*){"name": "model", "trainable": true, "expects_training_arg": true, "dtype": "float32", "batch_input_shape": null, "must_restore_from_config": false, "preserve_input_structure_in_config": false, "autocast": false, "class_name": "Functional", "config": {"name": "model", "layers": [{"class_name": "InputLayer", "config": {"batch_input_shape": {"class_name": "__tuple__", "items": [null, 1]}, "dtype": "float32", "sparse": false, "ragged": false, "name": "input_1"}, "name": "input_1", "inbound_nodes": []}, {"class_name": "Dense", "config": {"name": "dense", "trainable": true, "dtype": "float32", "units": 16, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}}, "bias_initializer": {"class_name": "Zeros", "config": {}}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense", "inbound_nodes": [[["input_1", 0, 0, {}]]]}, {"class_name": "Dense", "config": {"name": "dense_1", "trainable": true, "dtype": "float32", "units": 16, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}}, "bias_initializer": {"class_name": "Zeros", "config": {}}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_1", "inbound_nodes": [[["dense", 0, 0, {}]]]}, {"class_name": "Dense", "config": {"name": "dense_2", "trainable": true, "dtype": "float32", "units": 3, "activation": "linear", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}}, "bias_initializer": {"class_name": "Zeros", "config": {}}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_2", "inbound_nodes": [[["dense_1", 0, 0, {}]]]}], "input_layers": [["input_1", 0, 0]], "output_layers": [["dense_2", 0, 0]]}, "shared_object_id": 10, "input_spec": [{"class_name": "InputSpec", "config": {"dtype": null, "shape": {"class_name": "__tuple__", "items": [null, 1]}, "ndim": 2, "max_ndim": null, "min_ndim": null, "axes": {}}}], "build_input_shape": {"class_name": "TensorShape", "items": [null, 1]}, "is_graph_network": true, "full_save_spec": {"class_name": "__tuple__", "items": [[{"class_name": "TypeSpec", "type_spec": "tf.TensorSpec", "serialized": [{"class_name": "TensorShape", "items": [null, 1]}, "float32", "input_1"]}], {}]}, "save_spec": {"class_name": "TypeSpec", "type_spec": "tf.TensorSpec", "serialized": [{"class_name": "TensorShape", "items": [null, 1]}, "float32", "input_1"]}, "keras_version": "2.11.0", "backend": "tensorflow", "model_config": {"class_name": "Functional", "config": {"name": "model", "layers": [{"class_name": "InputLayer", "config": {"batch_input_shape": {"class_name": "__tuple__", "items": [null, 1]}, "dtype": "float32", "sparse": false, "ragged": false, "name": "input_1"}, "name": "input_1", "inbound_nodes": [], "shared_object_id": 0}, {"class_name": "Dense", "config": {"name": "dense", "trainable": true, "dtype": "float32", "units": 16, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 1}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 2}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense", "inbound_nodes": [[["input_1", 0, 0, {}]]], "shared_object_id": 3}, {"class_name": "Dense", "config": {"name": "dense_1", "trainable": true, "dtype": "float32", "units": 16, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 4}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 5}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_1", "inbound_nodes": [[["dense", 0, 0, {}]]], "shared_object_id": 6}, {"class_name": "Dense", "config": {"name": "dense_2", "trainable": true, "dtype": "float32", "units": 3, "activation": "linear", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 7}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 8}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "name": "dense_2", "inbound_nodes": [[["dense_1", 0, 0, {}]]], "shared_object_id": 9}], "input_layers": [["input_1", 0, 0]], "output_layers": [["dense_2", 0, 0]]}}, "training_config": {"loss": "mse", "metrics": null, "weighted_metrics": null, "loss_weights": null, "optimizer_config": {"class_name": "Custom>Adam", "config": {"name": "Adam", "weight_decay": null, "clipnorm": null, "global_clipnorm": null, "clipvalue": null, "use_ema": false, "ema_momentum": 0.99, "ema_overwrite_frequency": null, "jit_compile": true, "is_legacy_optimizer": false, "learning_rate": 0.004999999888241291, "beta_1": 0.9, "beta_2": 0.999, "epsilon": 1e-07, "amsgrad": false}}}}2 - root.layer-0"_tf_keras_input_layer*{"class_name": "InputLayer", "name": "input_1", "dtype": "float32", "sparse": false, "ragged": false, "batch_input_shape": {"class_name": "__tuple__", "items": [null, 1]}, "config": {"batch_input_shape": {"class_name": "__tuple__", "items": [null, 1]}, "dtype": "float32", "sparse": false, "ragged": false, "name": "input_1"}}2 -root.layer_with_weights-0"_tf_keras_layer*{"name": "dense", "trainable": true, "expects_training_arg": false, "dtype": "float32", "batch_input_shape": null, "stateful": false, "must_restore_from_config": false, "preserve_input_structure_in_config": false, "autocast": true, "class_name": "Dense", "config": {"name": "dense", "trainable": true, "dtype": "float32", "units": 16, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 1}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 2}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "inbound_nodes": [[["input_1", 0, 0, {}]]], "shared_object_id": 3, "input_spec": {"class_name": "InputSpec", "config": {"dtype": null, "shape": null, "ndim": null, "max_ndim": null, "min_ndim": 2, "axes": {"-1": 1}}, "shared_object_id": 12}, "build_input_shape": {"class_name": "TensorShape", "items": [null, 1]}}2 -root.layer_with_weights-1"_tf_keras_layer*{"name": "dense_1", "trainable": true, "expects_training_arg": false, "dtype": "float32", "batch_input_shape": null, "stateful": false, "must_restore_from_config": false, "preserve_input_structure_in_config": false, "autocast": true, "class_name": "Dense", "config": {"name": "dense_1", "trainable": true, "dtype": "float32", "units": 16, "activation": "relu", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 4}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 5}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "inbound_nodes": [[["dense", 0, 0, {}]]], "shared_object_id": 6, "input_spec": {"class_name": "InputSpec", "config": {"dtype": null, "shape": null, "ndim": null, "max_ndim": null, "min_ndim": 2, "axes": {"-1": 16}}, "shared_object_id": 13}, "build_input_shape": {"class_name": "TensorShape", "items": [null, 16]}}2 -root.layer_with_weights-2"_tf_keras_layer*{"name": "dense_2", "trainable": true, "expects_training_arg": false, "dtype": "float32", "batch_input_shape": null, "stateful": false, "must_restore_from_config": false, "preserve_input_structure_in_config": false, "autocast": true, "class_name": "Dense", "config": {"name": "dense_2", "trainable": true, "dtype": "float32", "units": 3, "activation": "linear", "use_bias": true, "kernel_initializer": {"class_name": "GlorotUniform", "config": {"seed": null}, "shared_object_id": 7}, "bias_initializer": {"class_name": "Zeros", "config": {}, "shared_object_id": 8}, "kernel_regularizer": null, "bias_regularizer": null, "activity_regularizer": null, "kernel_constraint": null, "bias_constraint": null}, "inbound_nodes": [[["dense_1", 0, 0, {}]]], "shared_object_id": 9, "input_spec": {"class_name": "InputSpec", "config": {"dtype": null, "shape": null, "ndim": null, "max_ndim": null, "min_ndim": 2, "axes": {"-1": 16}}, "shared_object_id": 14}, "build_input_shape": {"class_name": "TensorShape", "items": [null, 16]}}2 -Proot.keras_api.metrics.0"_tf_keras_metric*{"class_name": "Mean", "name": "loss", "dtype": "float32", "config": {"name": "loss", "dtype": "float32"}, "shared_object_id": 15}2 \ No newline at end of file diff --git a/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max5742_Epoch591_inTime20230217-100807.model/saved_model.pb b/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max5742_Epoch591_inTime20230217-100807.model/saved_model.pb deleted file mode 100644 index 70eb9ab5..00000000 Binary files a/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max5742_Epoch591_inTime20230217-100807.model/saved_model.pb and /dev/null differ diff --git a/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max5742_Epoch591_inTime20230217-100807.model/variables/variables.data-00000-of-00001 b/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max5742_Epoch591_inTime20230217-100807.model/variables/variables.data-00000-of-00001 deleted file mode 100644 index 260920e1..00000000 Binary files a/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max5742_Epoch591_inTime20230217-100807.model/variables/variables.data-00000-of-00001 and /dev/null differ diff --git a/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max5742_Epoch591_inTime20230217-100807.model/variables/variables.index b/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max5742_Epoch591_inTime20230217-100807.model/variables/variables.index deleted file mode 100644 index 22ebe19e..00000000 Binary files a/behavior_metrics/models/gazebo/rl_models/dqn/DQN_sp_16x16_LAPCOMPLETED_Max5742_Epoch591_inTime20230217-100807.model/variables/variables.index and /dev/null differ diff --git a/behavior_metrics/models/gazebo/rl_models/ppo/20231118-232134_LAPCOMPLETEDMaxReward-1084_Epoch-3 b/behavior_metrics/models/gazebo/rl_models/ppo/20231118-232134_LAPCOMPLETEDMaxReward-1084_Epoch-3 new file mode 100644 index 00000000..1219ed1b Binary files /dev/null and b/behavior_metrics/models/gazebo/rl_models/ppo/20231118-232134_LAPCOMPLETEDMaxReward-1084_Epoch-3 differ diff --git a/behavior_metrics/ui/gui/views/toolbar.py b/behavior_metrics/ui/gui/views/toolbar.py index 79e7a7a6..a790bf38 100644 --- a/behavior_metrics/ui/gui/views/toolbar.py +++ b/behavior_metrics/ui/gui/views/toolbar.py @@ -471,7 +471,9 @@ def create_brain_gb(self): self.brain_combobox = QComboBox() self.brain_combobox.setEnabled(True) - brains = [file.split(".")[0] for file in os.listdir(brains_path + self.configuration.robot_type) + environment_subpath = self.configuration.environment + '/' if self.configuration.environment is not None else "" + brains = [file.split(".")[0] for file + in os.listdir(brains_path + environment_subpath + self.configuration.robot_type) if file.endswith('.py') and file.split(".")[0] != '__init__'] self.brain_combobox.addItem('') self.brain_combobox.addItems(brains) @@ -702,7 +704,7 @@ def resume_simulation(self): brain = self.brain_combobox.currentText() + '.py' # load brain from controller - #if type(self.controller) != controller_carla.ControllerCarla: + # if type(self.controller) != controller_carla.ControllerCarla: # self.controller.reload_brain(brains_path + self.configuration.robot_type + '/' + brain) self.controller.resume_pilot() @@ -752,4 +754,3 @@ def open_close_simulator_gui(): environment.open_gzclient() else: environment.close_gzclient() - diff --git a/behavior_metrics/utils/configuration.py b/behavior_metrics/utils/configuration.py index 96ab6fa2..20667556 100644 --- a/behavior_metrics/utils/configuration.py +++ b/behavior_metrics/utils/configuration.py @@ -97,6 +97,7 @@ def initialize_configuration(self, config_data): """ robot = config_data['Behaviors']['Robot'] self.brain_path = robot['BrainPath'] + self.environment = robot.get('Environment', None) self.robot_type = robot['Type'] self.pilot_time_cycle = robot['PilotTimeCycle'] self.current_world = config_data['Behaviors']['Simulation']['World'] diff --git a/requirements.txt b/requirements.txt index c4ad8f58..2c16e019 100644 --- a/requirements.txt +++ b/requirements.txt @@ -16,7 +16,7 @@ matplotlib==3.1.2 kiwisolver==1.2 defusedxml==0.6.0 netifaces==0.10.9 -Pillow==10.0.1 +Pillow==10.2.0 pyglet==1.5.0 gym==0.17.3 requests==2.31.0 @@ -25,7 +25,7 @@ empy==3.3.2 vcstool==0.2.14 scikit-image==0.19.2 bagpy==0.4.10 -pycryptodomex==3.9.9 +pycryptodomex==3.19.1 torch==1.13.1 torchvision==0.14.1 tensorboard==2.11.0 @@ -38,4 +38,6 @@ transforms3d==0.4.1 pydantic==1.10.2 seaborn==0.12.2 pandas -scikit-learn==1.0.2 \ No newline at end of file +scikit-learn==1.0.2 +pygame +keras_preprocessing \ No newline at end of file