diff --git a/academy/settings.py b/academy/settings.py index fb309ebd7..3f295cf5f 100644 --- a/academy/settings.py +++ b/academy/settings.py @@ -175,4 +175,3 @@ ) CORS_ALLOW_CREDENTIALS = True - diff --git a/db.sqlite3 b/db.sqlite3 index a2b6e0199..1b2354fe7 100644 Binary files a/db.sqlite3 and b/db.sqlite3 differ diff --git a/exercises/models.py b/exercises/models.py index 89aa5a77c..5deba2d56 100644 --- a/exercises/models.py +++ b/exercises/models.py @@ -62,4 +62,4 @@ def context(self): 'indexs': exercise_assets.get('indexs', []), 'statics': exercise_assets.get('statics', [])} - return context + return context \ No newline at end of file diff --git a/exercises/static/exercises/assets/img/real_follow_person_newmanager_teaser.png b/exercises/static/exercises/assets/img/real_follow_person_newmanager_teaser.png new file mode 100644 index 000000000..9539c25e5 Binary files /dev/null and b/exercises/static/exercises/assets/img/real_follow_person_newmanager_teaser.png differ diff --git a/exercises/static/exercises/real_follow_person_newmanager/entry_point/ros2_humble/exercise.py b/exercises/static/exercises/real_follow_person_newmanager/entry_point/ros2_humble/exercise.py new file mode 100644 index 000000000..95343827f --- /dev/null +++ b/exercises/static/exercises/real_follow_person_newmanager/entry_point/ros2_humble/exercise.py @@ -0,0 +1,13 @@ +import os.path +from typing import Callable + +from src.manager.libs.applications.compatibility.physical_robot_exercise_wrapper_ros2 import CompatibilityExerciseWrapperRos2 + + +class Exercise(CompatibilityExerciseWrapperRos2): + def __init__(self, circuit: str, update_callback: Callable): + current_path = os.path.dirname(__file__) + + super(Exercise, self).__init__(exercise_command=f"{current_path}/../../python_template/ros2_humble/exercise.py 0.0.0.0", + gui_command=f"{current_path}/../../python_template/ros2_humble/gui.py 0.0.0.0 {circuit}", + update_callback=update_callback) diff --git a/exercises/static/exercises/real_follow_person_newmanager/launch/ros2_humble/follow_person.launch.py b/exercises/static/exercises/real_follow_person_newmanager/launch/ros2_humble/follow_person.launch.py new file mode 100644 index 000000000..193712a9d --- /dev/null +++ b/exercises/static/exercises/real_follow_person_newmanager/launch/ros2_humble/follow_person.launch.py @@ -0,0 +1,48 @@ +from launch import LaunchDescription +from launch_ros.actions import Node +from launch.substitutions import ThisLaunchFileDir +from launch.actions import IncludeLaunchDescription +from launch.launch_description_sources import PythonLaunchDescriptionSource +from ament_index_python.packages import get_package_share_directory +import os + +def generate_launch_description(): + + kobuki_launch_file_path = os.path.join(get_package_share_directory('kobuki_launch'), 'launch') + + kobuki_launcher = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(kobuki_launch_file_path, 'kobuki_base.launch.py') + ) + ) + + camera_node = Node( + package='usb_cam', + namespace='camera_node', + executable='usb_cam_node_exe', + name='camera' + ) + + rplidar_node = Node( + name='rplidar_composition', + package='rplidar_ros', + executable='rplidar_composition', + output='screen', + parameters=[{ + 'serial_port': '/dev/rplidar', + 'serial_baudrate': 115200, # A1 / A2 + # 'serial_baudrate': 256000, # A3 + 'frame_id': 'laser', + 'inverted': False, + 'angle_compensate': True, + }], + ) + + # Create the launch description and populate + ld = LaunchDescription() + + ld.add_action(kobuki_launcher) + ld.add_action(rplidar_node) + ld.add_action(camera_node) + + return ld \ No newline at end of file diff --git a/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/brain.py b/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/brain.py new file mode 100644 index 000000000..48103aa2b --- /dev/null +++ b/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/brain.py @@ -0,0 +1,153 @@ +import time +import threading +import multiprocessing +import sys +from datetime import datetime +import importlib + +from user_functions import GUIFunctions, HALFunctions +from console import start_console, close_console +from shared.value import SharedValue + +# The brain process class +class BrainProcess(multiprocessing.Process): + def __init__(self, code, exit_signal, stop_signal): + super(BrainProcess, self).__init__() + + # Initialize exit signal + self.exit_signal = exit_signal + self.stop_signal = stop_signal + + # Function definitions for users to use + self.hal = HALFunctions() + self.gui = GUIFunctions() + + # Time variables + self.brain_time_cycle = SharedValue('brain_time_cycle') + self.brain_ideal_cycle = SharedValue('brain_ideal_cycle') + self.iteration_counter = 0 + + # Get the sequential and iterative code + self.sequential_code = code[0] + self.iterative_code = code[1] + + # Function to run to start the process + def run(self): + # Two threads for running and measuring + self.measure_thread = threading.Thread(target=self.measure_frequency) + self.thread = threading.Thread(target=self.process_code) + + self.measure_thread.start() + self.thread.start() + + print("Brain Process Started!") + + self.exit_signal.wait() + + # The process function + def process_code(self): + # Redirect information to console + start_console() + + # Reference Environment for the exec() function + iterative_code, sequential_code = self.iterative_code, self.sequential_code + + # Whatever the code is, first step is to just stop! + self.hal.sendV(0) + self.hal.sendW(0) + + # The Python exec function + # Run the sequential part + gui_module, hal_module = self.generate_modules() + reference_environment = {"GUI": gui_module, "HAL": hal_module} + if sequential_code != "": + exec(sequential_code, reference_environment) + + # Run the iterative part inside template + # and keep the check for flag + while not self.exit_signal.is_set(): + while (self.stop_signal.is_set()): + if (self.exit_signal.is_set()): + break + time.sleep(0.1) + + start_time = datetime.now() + + # Execute the iterative portion + if iterative_code != "": + exec(iterative_code, reference_environment) + + # Template specifics to run! + finish_time = datetime.now() + dt = finish_time - start_time + ms = (dt.days * 24 * 60 * 60 + dt.seconds) * 1000 + dt.microseconds / 1000.0 + + # Keep updating the iteration counter + if(iterative_code == ""): + self.iteration_counter = 0 + else: + self.iteration_counter = self.iteration_counter + 1 + + # The code should be run for atleast the target time step + # If it's less put to sleep + # If it's more no problem as such, but we can change it! + brain_time_cycle = self.brain_time_cycle.get() + if(ms < brain_time_cycle): + time.sleep((brain_time_cycle - ms) / 1000.0) + + close_console() + print("Current Thread Joined!", flush=True) + + # Function to generate the modules for use in ACE Editor + def generate_modules(self): + # Define HAL module + hal_module = importlib.util.module_from_spec(importlib.machinery.ModuleSpec("HAL", None)) + hal_module.HAL = importlib.util.module_from_spec(importlib.machinery.ModuleSpec("HAL", None)) + hal_module.HAL.motors = importlib.util.module_from_spec(importlib.machinery.ModuleSpec("motors", None)) + + # Add HAL functions + hal_module.HAL.getImage = self.hal.getImage + hal_module.HAL.setV = self.hal.sendV + hal_module.HAL.setW = self.hal.sendW + hal_module.HAL.getLaserData = self.hal.getLaserData + hal_module.HAL.getBoundingBoxes = self.hal.getBoundingBoxes + hal_module.HAL.getPose3d = self.hal.getPose3d + + # Define GUI module + gui_module = importlib.util.module_from_spec(importlib.machinery.ModuleSpec("GUI", None)) + gui_module.GUI = importlib.util.module_from_spec(importlib.machinery.ModuleSpec("GUI", None)) + + # Add GUI functions + gui_module.GUI.showImage = self.gui.showImage + + # Adding modules to system + # Protip: The names should be different from + # other modules, otherwise some errors + sys.modules["HAL"] = hal_module + sys.modules["GUI"] = gui_module + + return gui_module, hal_module + + # Function to measure the frequency of iterations + def measure_frequency(self): + previous_time = datetime.now() + # An infinite loop + while not self.exit_signal.is_set(): + # Sleep for 2 seconds + time.sleep(2) + + # Measure the current time and subtract from the previous time to get real time interval + current_time = datetime.now() + dt = current_time - previous_time + ms = (dt.days * 24 * 60 * 60 + dt.seconds) * 1000 + dt.microseconds / 1000.0 + previous_time = current_time + + # Get the time period + try: + # Division by zero + self.brain_ideal_cycle.add(ms / self.iteration_counter) + except: + self.brain_ideal_cycle.add(0) + + # Reset the counter + self.iteration_counter = 0 \ No newline at end of file diff --git a/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/coco_labels.py b/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/coco_labels.py new file mode 100644 index 000000000..a8c3a9c19 --- /dev/null +++ b/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/coco_labels.py @@ -0,0 +1,185 @@ +LABEL_MAP = { + 0: "unlabeled", + 1: "person", + 2: "bicycle", + 3: "car", + 4: "motorcycle", + 5: "airplane", + 6: "bus", + 7: "train", + 8: "truck", + 9: "boat", + 10: "traffic", + 11: "fire", + 12: "street", + 13: "stop", + 14: "parking", + 15: "bench", + 16: "bird", + 17: "cat", + 18: "dog", + 19: "horse", + 20: "sheep", + 21: "cow", + 22: "elephant", + 23: "bear", + 24: "zebra", + 25: "giraffe", + 26: "hat", + 27: "backpack", + 28: "umbrella", + 29: "shoe", + 30: "eye", + 31: "handbag", + 32: "tie", + 33: "suitcase", + 34: "frisbee", + 35: "skis", + 36: "snowboard", + 37: "sports", + 38: "kite", + 39: "baseball", + 40: "baseball", + 41: "skateboard", + 42: "surfboard", + 43: "tennis", + 44: "bottle", + 45: "plate", + 46: "wine", + 47: "cup", + 48: "fork", + 49: "knife", + 50: "spoon", + 51: "bowl", + 52: "banana", + 53: "apple", + 54: "sandwich", + 55: "orange", + 56: "broccoli", + 57: "carrot", + 58: "hot", + 59: "pizza", + 60: "donut", + 61: "cake", + 62: "chair", + 63: "couch", + 64: "potted", + 65: "bed", + 66: "mirror", + 67: "dining", + 68: "window", + 69: "desk", + 70: "toilet", + 71: "door", + 72: "tv", + 73: "laptop", + 74: "mouse", + 75: "remote", + 76: "keyboard", + 77: "cell", + 78: "microwave", + 79: "oven", + 80: "toaster", + 81: "sink", + 82: "refrigerator", + 83: "blender", + 84: "book", + 85: "clock", + 86: "vase", + 87: "scissors", + 88: "teddy", + 89: "hair", + 90: "toothbrush", + 91: "hair", + 92: "banner", + 93: "blanket", + 94: "branch", + 95: "bridge", + 96: "building", + 97: "bush", + 98: "cabinet", + 99: "cage", + 100: "cardboard", + 101: "carpet", + 102: "ceiling", + 103: "ceiling", + 104: "cloth", + 105: "clothes", + 106: "clouds", + 107: "counter", + 108: "cupboard", + 109: "curtain", + 110: "desk", + 111: "dirt", + 112: "door", + 113: "fence", + 114: "floor", + 115: "floor", + 116: "floor", + 117: "floor", + 118: "floor", + 119: "flower", + 120: "fog", + 121: "food", + 122: "fruit", + 123: "furniture", + 124: "grass", + 125: "gravel", + 126: "ground", + 127: "hill", + 128: "house", + 129: "leaves", + 130: "light", + 131: "mat", + 132: "metal", + 133: "mirror", + 134: "moss", + 135: "mountain", + 136: "mud", + 137: "napkin", + 138: "net", + 139: "paper", + 140: "pavement", + 141: "pillow", + 142: "plant", + 143: "plastic", + 144: "platform", + 145: "playingfield", + 146: "railing", + 147: "railroad", + 148: "river", + 149: "road", + 150: "rock", + 151: "roof", + 152: "rug", + 153: "salad", + 154: "sand", + 155: "sea", + 156: "shelf", + 157: "sky", + 158: "skyscraper", + 159: "snow", + 160: "solid", + 161: "stairs", + 162: "stone", + 163: "straw", + 164: "structural", + 165: "table", + 166: "tent", + 167: "textile", + 168: "towel", + 169: "tree", + 170: "vegetable", + 171: "wall", + 172: "wall", + 173: "wall", + 174: "wall", + 175: "wall", + 176: "wall", + 177: "wall", + 178: "water", + 179: "waterdrops", + 180: "window", + 181: "window", + 182: "wood" +} diff --git a/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/console.py b/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/console.py new file mode 100644 index 000000000..5335016ae --- /dev/null +++ b/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/console.py @@ -0,0 +1,18 @@ +# Functions to start and close console +import os +import sys + +def start_console(): + # Get all the file descriptors and choose the latest one + fds = os.listdir("/dev/pts/") + fds.sort() + console_fd = fds[-2] + + sys.stderr = open('/dev/pts/' + console_fd, 'w') + sys.stdout = open('/dev/pts/' + console_fd, 'w') + sys.stdin = open('/dev/pts/' + console_fd, 'w') + +def close_console(): + sys.stderr.close() + sys.stdout.close() + sys.stdin.close() diff --git a/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/exercise.py b/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/exercise.py new file mode 100644 index 000000000..89d712a9b --- /dev/null +++ b/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/exercise.py @@ -0,0 +1,276 @@ +#!/usr/bin/env python +import os +from websocket_server import WebsocketServer +import time +import threading +import multiprocessing +import subprocess +import sys +import re +import json +import queue + +from shared.value import SharedValue + +from hal import HAL +from brain import BrainProcess + + + +class Template: + # Initialize class variables + # self.time_cycle to run an execution for atleast 1 second + # self.process for the current running process + def __init__(self): + print("Exercise initializing", flush=True) + self.brain_process = None + self.reload = multiprocessing.Event() + self.stop_brain = multiprocessing.Event() + self.user_code = "" + + # Time variables + self.brain_time_cycle = SharedValue('brain_time_cycle') + self.brain_ideal_cycle = SharedValue('brain_ideal_cycle') + self.real_time_factor = 0 + + self.frequency_message = {'brain': '', 'gui': '', 'rtf': ''} + + # GUI variables + self.gui_time_cycle = SharedValue('gui_time_cycle') + self.gui_ideal_cycle = SharedValue('gui_ideal_cycle') + + self.server = None + self.client = None + self.host = sys.argv[1] + + # Initialize the GUI and HAL behind the scenes + self.hal = HAL() + + print("Exercise initialized", flush=True) + + # Function for saving + def save_code(self, source_code): + with open('code/academy.py', 'w') as code_file: + code_file.write(source_code) + + # Function for loading + def load_code(self): + with open('code/academy.py', 'r') as code_file: + source_code = code_file.read() + + return source_code + + # Function to parse the code + # A few assumptions: + # 1. The user always passes sequential and iterative codes + # 2. Only a single infinite loop + def parse_code(self, source_code): + # Check for save/load + if(source_code[:5] == "#save"): + source_code = source_code[5:] + self.save_code(source_code) + return "", "" + + elif(source_code[:5] == "#load"): + source_code = source_code + self.load_code() + self.server.send_message(self.client, source_code) + + return "", "" + + else: + sequential_code, iterative_code = self.seperate_seq_iter(source_code[6:]) + return sequential_code, iterative_code + + # Function to seperate the iterative and sequential code + def seperate_seq_iter(self, source_code): + if source_code == "": + return "", "" + + # Search for an instance of while True + infinite_loop = re.search(r'[^ ]while\s*\(\s*True\s*\)\s*:|[^ ]while\s*True\s*:|[^ ]while\s*1\s*:|[^ ]while\s*\(\s*1\s*\)\s*:', source_code) + + # Seperate the content inside while True and the other + # (Seperating the sequential and iterative part!) + try: + start_index = infinite_loop.start() + iterative_code = source_code[start_index:] + sequential_code = source_code[:start_index] + + # Remove while True: syntax from the code + # And remove the the 4 spaces indentation before each command + iterative_code = re.sub(r'[^ ]while\s*\(\s*True\s*\)\s*:|[^ ]while\s*True\s*:|[^ ]while\s*1\s*:|[^ ]while\s*\(\s*1\s*\)\s*:', '', iterative_code) + # Add newlines to match line on bug report + extra_lines = sequential_code.count('\n') + while (extra_lines >= 0): + iterative_code = '\n' + iterative_code + extra_lines -= 1 + iterative_code = re.sub(r'^[ ]{4}', '', iterative_code, flags=re.M) + + except: + sequential_code = source_code + iterative_code = "" + + return sequential_code, iterative_code + + # Function to maintain thread execution + def execute_thread(self, source_code): + # Keep checking until the thread is alive + # The thread will die when the coming iteration reads the flag + if(self.brain_process != None): + while self.brain_process.is_alive(): + pass + + # Turn the flag down, the iteration has successfully stopped! + self.reload.clear() + # New thread execution + code = self.parse_code(source_code) + if code[0] == "" and code[1] == "": + return + self.brain_process = BrainProcess(code, self.reload, self.stop_brain) + self.brain_process.start() + self.send_code_message() + + # Function to read and set frequency from incoming message + def read_frequency_message(self, message): + frequency_message = json.loads(message) + + # Set brain frequency + frequency = float(frequency_message["brain"]) + self.brain_time_cycle.add(1000.0 / frequency) + + # Set gui frequency + frequency = float(frequency_message["gui"]) + self.gui_time_cycle.add(1000.0 / frequency) + + return + + # Function to track the real time factor from Gazebo statistics + # https://stackoverflow.com/a/17698359 + # (For reference, Python3 solution specified in the same answer) + def track_stats(self): + args = ["gz", "stats", "-p"] + # Prints gz statistics. "-p": Output comma-separated values containing- + # real-time factor (percent), simtime (sec), realtime (sec), paused (T or F) + stats_process = subprocess.Popen(args, stdout=subprocess.PIPE, bufsize=0) + # bufsize=1 enables line-bufferred mode (the input buffer is flushed + # automatically on newlines if you would write to process.stdin ) + with stats_process.stdout: + for line in iter(stats_process.stdout.readline, b''): + stats_list = [x.strip() for x in line.split(b',')] + self.real_time_factor = stats_list[0].decode("utf-8") + + # Function to generate and send frequency messages + + def send_frequency_message(self): + # This function generates and sends frequency measures of the brain and gui + brain_frequency = 0 + gui_frequency = 0 + try: + brain_frequency = round(1000 / self.brain_ideal_cycle.get(), 1) + except ZeroDivisionError: + brain_frequency = 0 + + try: + gui_frequency = round(1000 / self.gui_ideal_cycle.get(), 1) + except ZeroDivisionError: + gui_frequency = 0 + + self.frequency_message["brain"] = brain_frequency + self.frequency_message["gui"] = gui_frequency + self.frequency_message["rtf"] = self.real_time_factor + + message = "#freq" + json.dumps(self.frequency_message) + self.server.send_message(self.client, message) + + def send_ping_message(self): + self.server.send_message(self.client, "#ping") + + # Function to notify the front end that the code was received and sent to execution + def send_code_message(self): + self.server.send_message(self.client, "#exec") + + # The websocket function + # Gets called when there is an incoming message from the client + def handle(self, client, server, message): + if(message[:5] == "#freq"): + frequency_message = message[5:] + self.read_frequency_message(frequency_message) + time.sleep(1) + self.send_frequency_message() + return + + elif(message[:5] == "#ping"): + time.sleep(1) + self.send_ping_message() + return + + elif (message[:5] == "#code"): + try: + # Once received turn the reload flag up and send it to execute_thread function + self.user_code = message + self.reload.set() + self.stop_brain.clear() + self.execute_thread(self.user_code) + + except: + pass + + elif (message[:5] == "#stop"): + self.stop_brain.set() + self.server.send_message(self.client, "#stpd") + + elif (message[:5] == "#play"): + self.stop_brain.clear() + + elif (message[:5] == "#rest"): + self.reload.set() + self.stop_brain.clear() + self.execute_thread(self.user_code) + + # Function that gets called when the server is connected + def connected(self, client, server): + self.client = client + # Start the HAL update thread + message ="#strt" +json.dumps("Starting HAL thread") + self.server.send_message(self.client, message) + self.hal.start_thread() + + # Start real time factor tracker thread + self.stats_thread = threading.Thread(target=self.track_stats) + self.stats_thread.start() + + # Initialize the ping message + self.send_frequency_message() + + print(client, 'connected') + + # Function that gets called when the connected closes + def handle_close(self, client, server): + print(client, 'closed') + + def run_server(self): + self.server = WebsocketServer(port=1905, host=self.host) + self.server.set_fn_new_client(self.connected) + self.server.set_fn_client_left(self.handle_close) + self.server.set_fn_message_received(self.handle) + + home_dir = os.path.expanduser('~') + + logged = False + while not logged: + try: + f = open(f"{home_dir}/ws_code.log", "w") + f.write("websocket_code=ready") + f.close() + logged = True + except: + print("~/ws_code.log could not be opened for write", flush=True) + time.sleep(0.1) + + self.server.run_forever() + + +# Execute! +if __name__ == "__main__": + server = Template() + server.run_server() diff --git a/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/gui.py b/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/gui.py new file mode 100644 index 000000000..837b41f86 --- /dev/null +++ b/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/gui.py @@ -0,0 +1,225 @@ +import json +import os + +import rclpy +import cv2 +import sys +import base64 +import threading +import time +import numpy as np +from datetime import datetime +from websocket_server import WebsocketServer +import multiprocessing + +from shared.image import SharedImage +from shared.image import SharedImage +from shared.value import SharedValue + +# Graphical User Interface Class +class GUI: + # Initialization function + # The actual initialization + def __init__(self, host): + rclpy.init() + rclpy.create_node('GUI') + + self.payload = {'image':'', 'v':'','w':''} + self.server = None + self.client = None + + self.host = host + + # Image variable host + self.shared_image = SharedImage("guiimage") + + # Get HAL variables + self.shared_v = SharedValue("velocity") + self.shared_w = SharedValue("angular") + + # Event objects for multiprocessing + self.ack_event = multiprocessing.Event() + self.cli_event = multiprocessing.Event() + + # Start server thread + t = threading.Thread(target=self.run_server) + t.start() + + # Function to prepare image payload + # Encodes the image as a JSON string and sends through the WS + def payloadImage(self): + image = self.shared_image.get() + payload = {'image': '', 'shape': ''} + + shape = image.shape + frame = cv2.imencode('.JPEG', image)[1] + encoded_image = base64.b64encode(frame) + + payload['image'] = encoded_image.decode('utf-8') + payload['shape'] = shape + + return payload + + # Function for student to call + def showImage(self, image): + self.image_show_lock.acquire() + self.image_to_be_shown = image + self.image_to_be_shown_updated = True + self.image_show_lock.release() + + # Function to get the client + # Called when a new client is received + def get_client(self, client, server): + self.client = client + self.cli_event.set() + + print(client, 'connected') + + # Update the gui + def update_gui(self): + # Payload Image Message + payload = self.payloadImage() + self.payload["image"] = json.dumps(payload) + + # Payload V Message + v_message = str(self.shared_v.get()) + self.payload["v"] = v_message + + # Payload W Message + w_message = str(self.shared_w.get()) + self.payload["w"] = w_message + + message = "#gui" + json.dumps(self.payload) + self.server.send_message(self.client, message) + + # Function to read the message from websocket + # Gets called when there is an incoming message from the client + def get_message(self, client, server, message): + # Acknowledge Message for GUI Thread + if(message[:4] == "#ack"): + # Set acknowledgement flag + self.ack_event.set() + # Reset message + elif(message[:5] == "#rest"): + self.reset_gui() + + + # Function that gets called when the connected closes + def handle_close(self, client, server): + print(client, 'closed') + + # Activate the server + def run_server(self): + self.server = WebsocketServer(port=2303, host=self.host) + self.server.set_fn_new_client(self.get_client) + self.server.set_fn_message_received(self.get_message) + self.server.set_fn_client_left(self.handle_close) + + home_dir = os.path.expanduser('~') + + logged = False + while not logged: + try: + f = open(f"{home_dir}/ws_gui.log", "w") + f.write("websocket_gui=ready") + f.close() + logged = True + except: + time.sleep(0.1) + + self.server.run_forever() + + +# This class decouples the user thread +# and the GUI update thread +class ProcessGUI(multiprocessing.Process): + def __init__(self): + super(ProcessGUI, self).__init__() + + self.host = sys.argv[1] + + # Time variables + self.time_cycle = SharedValue("gui_time_cycle") + self.ideal_cycle = SharedValue("gui_ideal_cycle") + self.iteration_counter = 0 + + # Function to initialize events + def initialize_events(self): + # Events + self.ack_event = self.gui.ack_event + self.cli_event = self.gui.cli_event + self.exit_signal = multiprocessing.Event() + + # Function to start the execution of threads + def run(self): + # Initialize GUI + self.gui = GUI(self.host) + self.initialize_events() + + # Wait for client before starting + self.cli_event.wait() + + self.measure_thread = threading.Thread(target=self.measure_thread) + self.thread = threading.Thread(target=self.run_gui) + + self.measure_thread.start() + self.thread.start() + + print("GUI Process Started!") + + self.exit_signal.wait() + + # The measuring thread to measure frequency + def measure_thread(self): + previous_time = datetime.now() + while(True): + # Sleep for 2 seconds + time.sleep(2) + + # Measure the current time and subtract from previous time to get real time interval + current_time = datetime.now() + dt = current_time - previous_time + ms = (dt.days * 24 * 60 * 60 + dt.seconds) * 1000 + dt.microseconds / 1000.0 + previous_time = current_time + + # Get the time period + try: + # Division by zero + self.ideal_cycle.add(ms / self.iteration_counter) + except: + self.ideal_cycle.add(0) + + # Reset the counter + self.iteration_counter = 0 + + # The main thread of execution + def run_gui(self): + while(True): + start_time = datetime.now() + # Send update signal + self.gui.update_gui() + + # Wait for acknowldege signal + self.ack_event.wait() + self.ack_event.clear() + + finish_time = datetime.now() + self.iteration_counter = self.iteration_counter + 1 + + dt = finish_time - start_time + ms = (dt.days * 24 * 60 * 60 + dt.seconds) * 1000 + dt.microseconds / 1000.0 + + time_cycle = self.time_cycle.get() + + if(ms < time_cycle): + time.sleep((time_cycle-ms) / 1000.0) + + self.exit_signal.set() + + # Functions to handle auxillary GUI functions + def reset_gui(): + self.gui.reset_gui() + +if __name__ == "__main__": + gui = ProcessGUI() + gui.start() diff --git a/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/hal.py b/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/hal.py new file mode 100644 index 000000000..b819140d6 --- /dev/null +++ b/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/hal.py @@ -0,0 +1,144 @@ +import rclpy +import sys + +import numpy as np +import threading +import time +from datetime import datetime + +from interfaces.camera import ListenerCamera +from interfaces.motors import PublisherMotors +from interfaces.laser import ListenerLaser +from interfaces.pose3d import ListenerPose3d + +from shared.image import SharedImage +from shared.value import SharedValue +from shared.laserdata import SharedLaserData +from shared.pose3d import SharedPose3D + +from user_functions import HALFunctions + +# Hardware Abstraction Layer + +class HAL: + IMG_WIDTH = 320 + IMG_HEIGHT = 240 + + def __init__(self): + print("HAL initializing", flush=True) + rclpy.init(args=sys.argv) + rclpy.create_node('HAL') + + # Shared memory variables + self.shared_image = SharedImage("halimage") + self.shared_v = SharedValue("velocity") + self.shared_w = SharedValue("angular") + self.shared_laserdata = SharedLaserData("laserdata") + self.shared_pose = SharedPose3D("pose") + + # ROS Topics + self.motors = PublisherMotors("/commands/velocity", 4, 0.3) + self.camera = ListenerCamera("/camera_node/image_raw") + self.laser = ListenerLaser("/scan") + self.odometry = ListenerPose3d("/odom") + + self.start_time = 0 + + # Update thread + self.thread = ThreadHAL(self.update_hal) + print("HAL initialized", flush=True) + + # Function to start the update thread + def start_thread(self): + print("HAL thread starting", flush=True) + self.start_time = time.time() + self.thread.start() + + # Get laser data from ROS Driver + def getLaserData(self): + try: + rclpy.spin_once(self.laser) + values = self.laser.getLaserData().values + self.shared_laserdata.add(values) + except Exception as e: + print(f"Exception in hal getLaserData {repr(e)}") + + # Get pose from ROS Driver + def getPose3d(self): + try: + rclpy.spin_once(self.odometry) + pose = self.odometry.getPose3d() + self.shared_pose.add(pose) + except Exception as e: + print(f"Exception in hal getPose3d {repr(e)}") + + # Get Image from ROS Driver Camera + def getImage(self): + try: + rclpy.spin_once(self.camera) + image = self.camera.getImage().data + self.shared_image.add(image) + except Exception as e: + print(f"Exception in hal getImage {repr(e)}") + + # Set the velocity + def setV(self): + velocity = self.shared_v.get() + self.motors.sendV(velocity) + + # Get the velocity + def getV(self): + velocity = self.shared_v.get() + return velocity + + # Get the angular velocity + def getW(self): + angular = self.shared_w.get() + return angular + + # Set the angular velocity + def setW(self): + angular = self.shared_w.get() + self.motors.sendW(angular) + + def getBoundingBoxes(self, img): + return HALFunctions.getBoundingBoxes(img) + + def update_hal(self): + self.getLaserData() + self.getImage() + self.setV() + self.setW() + self.getPose3d() + + # Destructor function to close all fds + def __del__(self): + self.shared_image.close() + self.shared_v.close() + self.shared_w.close() + self.shared_laserdata.close() + self.shared_pose.close() + + +class ThreadHAL(threading.Thread): + def __init__(self, update_function): + super(ThreadHAL, self).__init__() + self.time_cycle = 80 + self.update_function = update_function + + def run(self): + print("Starting HAL thread", flush=True) + while (True): + start_time = datetime.now() + + # print(f"Calling update function inside hal thread") + self.update_function() + + finish_time = datetime.now() + + dt = finish_time - start_time + ms = (dt.days * 24 * 60 * 60 + dt.seconds) * \ + 1000 + dt.microseconds / 1000.0 + + if (ms < self.time_cycle): + time.sleep((self.time_cycle - ms) / 1000.0) diff --git a/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/interfaces/__init__.py b/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/interfaces/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/interfaces/bounding_boxes.py b/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/interfaces/bounding_boxes.py new file mode 100644 index 000000000..e1ad6aa61 --- /dev/null +++ b/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/interfaces/bounding_boxes.py @@ -0,0 +1,87 @@ +import rclpy +from rclpy.node import Node +import threading +from darknet_ros_msgs.msg import BoundingBoxes + +def debug(cad): + f = open("mydebug", "a") + f.write(cad) + f.close() + +class BoundingBoxData: + + def __init__(self): + self.probability = 0 + self.xmin = 0 + self.ymin = 0 + self.xmax = 0 + self.ymax = 0 + self.id = 0 + self.class_id = "" + + +def BoundingBox2BoundingBoxData(bbox): + bounding_box = BoundingBoxData() + bounding_box.probability = bbox.probability + bounding_box.xmin = bbox.xmin + bounding_box.ymin = bbox.ymin + bounding_box.xmax = bbox.xmax + bounding_box.ymax = bbox.ymax + bounding_box.id = bbox.id + bounding_box.class_id = bbox.class_id + + return bounding_box + + +class BoundingBoxesData: + + def __init__(self): + self.timeStamp = 0 + self.bounding_boxes = [] + + def __str__(self): + s = "TimeStamp: " + str(self.timeStamp) + "\nBoundingBoxes: " + str(self.bounding_boxes) + "\n" + return s + + +def BoundingBoxes2BoundingBoxesData(bboxes): + + bounding_boxes = BoundingBoxesData() + bounding_boxes.bounding_boxes = bboxes.bounding_boxes + bounding_boxes.timeStamp = bboxes.header.stamp.sec + (bboxes.header.stamp.nanosec *1e-9) + return bounding_boxes + +class ListenerBoundingBoxes(Node): + ''' + Bounding Boxes Subscriber + ''' + def __init__(self, topic): + super().__init__("bounding_boxes_subscriber_node") + self.topic = topic + self.data = BoundingBoxesData() + self.sub = None + self.lock = threading.Lock() + self.start() + + def __callback(self, bboxes): + bounding_boxes = BoundingBoxes2BoundingBoxesData(bboxes) + + self.lock.acquire() + self.data = bounding_boxes + self.lock.release() + + def start(self): + self.sub = self.create_subscription(BoundingBoxes, self.topic, self.__callback, 10) + + def stop(self): + self.sub.unregister() + + def getBoundingBoxes(self): + print("Get Bouding Boxes") # BORRAR + self.lock.acquire() + bounding_boxes = self.data + self.lock.release() + + return bounding_boxes + + diff --git a/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/interfaces/camera.py b/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/interfaces/camera.py new file mode 100644 index 000000000..5272fb600 --- /dev/null +++ b/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/interfaces/camera.py @@ -0,0 +1,88 @@ +import rclpy +from rclpy.node import Node +import sensor_msgs.msg +import threading +from math import pi as PI +import cv2 +from cv_bridge import CvBridge, CvBridgeError + + +MAXRANGE = 8 #max length received from imageD +MINRANGE = 0 + +def imageMsg2Image(img, bridge): + + image = Image() + + image.width = img.width + image.height = img.height + image.format = "BGR8" + image.timeStamp = img.header.stamp.sec + (img.header.stamp.nanosec *1e-9) + cv_image=0 + if (img.encoding[-2:] == "C1"): + gray_img_buff = bridge.imgmsg_to_cv2(img, img.encoding) + cv_image = depthToRGB8(gray_img_buff, img.encoding) + else: + cv_image = bridge.imgmsg_to_cv2(img, "bgr8") + + image.data = cv_image + return image + +import numpy as np + + +class Image: + + def __init__(self): + + self.height = 480 # Image height [pixels] + self.width = 640 # Image width [pixels] + self.timeStamp = 0 # Time stamp [s] */ + self.format = "" # Image format string (RGB8, BGR,...) + self.data = np.zeros((self.height, self.width, 3), np.uint8) # The image data itself + self.data.shape = self.height, self.width, 3 + + + def __str__(self): + s = "Image: {\n height: " + str(self.height) + "\n width: " + str(self.width) + s = s + "\n format: " + self.format + "\n timeStamp: " + str(self.timeStamp) + s = s + "\n data: " + str(self.data) + "\n}" + return s + + +class ListenerCamera(Node): + + def __init__(self, topic): + super().__init__("camera_subscriber_node") + + self.topic = topic + self.data = Image() + self.sub = None + self.lock = threading.Lock() + + self.bridge = CvBridge() + self.start() + + def __callback (self, msg): + image = imageMsg2Image(msg, self.bridge) + + self.lock.acquire() + self.data = image + self.lock.release() + + def stop(self): + self.sub.unregister() + + def start (self): + self.sub = self.create_subscription(sensor_msgs.msg.Image, self.topic , self.__callback, 10) + + def getImage(self): + + self.lock.acquire() + image = self.data + self.lock.release() + + return image + + def hasproxy (self): + return hasattr(self,"sub") and self.sub diff --git a/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/interfaces/laser.py b/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/interfaces/laser.py new file mode 100644 index 000000000..db9ef0c9c --- /dev/null +++ b/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/interfaces/laser.py @@ -0,0 +1,119 @@ +from rclpy.node import Node +import sensor_msgs.msg +import threading +from math import pi as PI + +def debug(cad): + f = open("mydebug", "a") + f.write(cad) + f.close() + +class LaserData (): + + def __init__(self): + + self.values = [] # meters + self.minAngle = 0 # Angle of first value (rads) + self.maxAngle = 0 # Angle of last value (rads) + self.minRange = 0 # Max Range posible (meters) + self.maxRange = 0 #Min Range posible (meters) + self.timeStamp = 0 # seconds + + + def __str__(self): + s = "LaserData: {\n minAngle: " + str(self.minAngle) + "\n maxAngle: " + str(self.maxAngle) + s = s + "\n minRange: " + str(self.minRange) + "\n maxRange: " + str(self.maxRange) + s = s + "\n timeStamp: " + str(self.timeStamp) + "\n values: " + str(self.values) + "\n}" + return s + + +def laserScan2LaserData(scan): + ''' + Translates from ROS LaserScan to JderobotTypes LaserData. + + @param scan: ROS LaserScan to translate + + @type scan: LaserScan + + @return a LaserData translated from scan + + ''' + laser = LaserData() + laser.values = scan.ranges + ''' + ROS Angle Map JdeRobot Angle Map + 0 PI/2 + | | + | | + PI/2 --------- -PI/2 PI --------- 0 + | | + | | + ''' + laser.minAngle = scan.angle_min + PI/2 + laser.maxAngle = scan.angle_max + PI/2 + laser.maxRange = scan.range_max + laser.minRange = scan.range_min + laser.timeStamp = scan.header.stamp.sec + (scan.header.stamp.nanosec *1e-9) + return laser + +class ListenerLaser(Node): + ''' + ROS Laser Subscriber. Laser Client to Receive Laser Scans from ROS nodes. + ''' + def __init__(self, topic): + ''' + ListenerLaser Constructor. + + @param topic: ROS topic to subscribe + + @type topic: String + + ''' + super().__init__("laser_subscriber_node") + self.topic = topic + self.data = LaserData() + self.sub= None + self.lock = threading.Lock() + self.start() + + def __callback (self, scan): + ''' + Callback function to receive and save Laser Scans. + + @param scan: ROS LaserScan received + + @type scan: LaserScan + + ''' + laser = laserScan2LaserData(scan) + + self.lock.acquire() + self.data = laser + self.lock.release() + + def stop(self): + ''' + Stops (Unregisters) the client. + + ''' + self.sub.unregister() + + def start (self): + ''' + Starts (Subscribes) the client. + + ''' + self.sub = self.create_subscription(sensor_msgs.msg.LaserScan, self.topic, self.__callback, 10) + + def getLaserData(self): + ''' + Returns last LaserData. + + @return last JdeRobotTypes LaserData saved + + ''' + self.lock.acquire() + laser = self.data + self.lock.release() + + return laser diff --git a/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/interfaces/motors.py b/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/interfaces/motors.py new file mode 100644 index 000000000..138be49aa --- /dev/null +++ b/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/interfaces/motors.py @@ -0,0 +1,124 @@ +import rclpy +from geometry_msgs.msg import Twist +import threading +from math import pi as PI +from .threadPublisher import ThreadPublisher + + + +def cmdvel2Twist(vel): + + tw = Twist() + tw.linear.x = float(vel.vx) + tw.linear.y = float(vel.vy) + tw.linear.z = float(vel.vz) + tw.angular.x = float(vel.ax) + tw.angular.y = float(vel.ay) + tw.angular.z = float(vel.az) + + return tw + + +class CMDVel (): + + def __init__(self): + + self.vx = 0 # vel in x[m/s] (use this for V in wheeled robots) + self.vy = 0 # vel in y[m/s] + self.vz = 0 # vel in z[m/s] + self.ax = 0 # angular vel in X axis [rad/s] + self.ay = 0 # angular vel in X axis [rad/s] + self.az = 0 # angular vel in Z axis [rad/s] (use this for W in wheeled robots) + self.timeStamp = 0 # Time stamp [s] + + + def __str__(self): + s = "CMDVel: {\n vx: " + str(self.vx) + "\n vy: " + str(self.vy) + s = s + "\n vz: " + str(self.vz) + "\n ax: " + str(self.ax) + s = s + "\n ay: " + str(self.ay) + "\n az: " + str(self.az) + s = s + "\n timeStamp: " + str(self.timeStamp) + "\n}" + return s + +class PublisherMotors: + + def __init__(self, topic, maxV, maxW): + + self.maxW = maxW + self.maxV = maxV + + self.node = rclpy.create_node('PublisherMotors') + self.topic = topic + self.data = CMDVel() + self.pub = self.node.create_publisher(Twist, self.topic, 10 ) + + self.lock = threading.Lock() + + self.kill_event = threading.Event() + self.thread = ThreadPublisher(self, self.kill_event) + + self.thread.daemon = True + self.start() + + def publish (self): + + self.lock.acquire() + tw = cmdvel2Twist(self.data) + self.lock.release() + self.pub.publish(tw) + + def stop(self): + + self.kill_event.set() + self.pub.unregister() + + def start (self): + + self.kill_event.clear() + self.thread.start() + + + + def getMaxW(self): + return self.maxW + + def getMaxV(self): + return self.maxV + + + def sendVelocities(self, vel): + + self.lock.acquire() + self.data = vel + self.lock.release() + + def sendV(self, v): + + self.sendVX(v) + + def sendL(self, l): + + self.sendVY(l) + + def sendW(self, w): + + self.sendAZ(w) + + def sendVX(self, vx): + + self.lock.acquire() + self.data.vx = float(vx) + self.lock.release() + + def sendVY(self, vy): + + self.lock.acquire() + self.data.vy = float(vy) + self.lock.release() + + def sendAZ(self, az): + + self.lock.acquire() + self.data.az = float(az) + self.lock.release() + + diff --git a/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/interfaces/pose3d.py b/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/interfaces/pose3d.py new file mode 100644 index 000000000..4ec38f533 --- /dev/null +++ b/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/interfaces/pose3d.py @@ -0,0 +1,179 @@ +from rclpy.node import Node +import threading +from math import asin, atan2, pi +import nav_msgs.msg + +def quat2Yaw(qw, qx, qy, qz): + ''' + Translates from Quaternion to Yaw. + + @param qw,qx,qy,qz: Quaternion values + + @type qw,qx,qy,qz: float + + @return Yaw value translated from Quaternion + + ''' + rotateZa0=2.0*(qx*qy + qw*qz) + rotateZa1=qw*qw + qx*qx - qy*qy - qz*qz + rotateZ=0.0 + if(rotateZa0 != 0.0 and rotateZa1 != 0.0): + rotateZ=atan2(rotateZa0,rotateZa1) + return rotateZ + +def quat2Pitch(qw, qx, qy, qz): + ''' + Translates from Quaternion to Pitch. + + @param qw,qx,qy,qz: Quaternion values + + @type qw,qx,qy,qz: float + + @return Pitch value translated from Quaternion + + ''' + + rotateYa0=-2.0*(qx*qz - qw*qy) + rotateY=0.0 + if(rotateYa0 >= 1.0): + rotateY = pi/2.0 + elif(rotateYa0 <= -1.0): + rotateY = -pi/2.0 + else: + rotateY = asin(rotateYa0) + + return rotateY + +def quat2Roll (qw, qx, qy, qz): + ''' + Translates from Quaternion to Roll. + + @param qw,qx,qy,qz: Quaternion values + + @type qw,qx,qy,qz: float + + @return Roll value translated from Quaternion + + ''' + rotateXa0=2.0*(qy*qz + qw*qx) + rotateXa1=qw*qw - qx*qx - qy*qy + qz*qz + rotateX=0.0 + + if(rotateXa0 != 0.0 and rotateXa1 != 0.0): + rotateX=atan2(rotateXa0, rotateXa1) + return rotateX + + +def odometry2Pose3D(odom): + ''' + Translates from ROS Odometry to JderobotTypes Pose3d. + + @param odom: ROS Odometry to translate + + @type odom: Odometry + + @return a Pose3d translated from odom + + ''' + pose = Pose3d() + ori = odom.pose.pose.orientation + + pose.x = odom.pose.pose.position.x + pose.y = odom.pose.pose.position.y + pose.z = odom.pose.pose.position.z + #pose.h = odom.pose.pose.position.h + pose.yaw = quat2Yaw(ori.w, ori.x, ori.y, ori.z) + pose.pitch = quat2Pitch(ori.w, ori.x, ori.y, ori.z) + pose.roll = quat2Roll(ori.w, ori.x, ori.y, ori.z) + pose.q = [ori.w, ori.x, ori.y, ori.z] + pose.timeStamp = odom.header.stamp.sec + (odom.header.stamp.nanosec *1e-9) + + return pose + +class Pose3d (): + + def __init__(self): + + self.x = 0 # X coord [meters] + self.y = 0 # Y coord [meters] + self.z = 0 # Z coord [meters] + self.h = 1 # H param + self.yaw = 0 #Yaw angle[rads] + self.pitch = 0 # Pitch angle[rads] + self.roll = 0 # Roll angle[rads] + self.q = [0,0,0,0] # Quaternion + self.timeStamp = 0 # Time stamp [s] + + + def __str__(self): + s = "Pose3D: {\n x: " + str(self.x) + "\n y: " + str(self.y) + s = s + "\n z: " + str(self.z) + "\n H: " + str(self.h) + s = s + "\n Yaw: " + str(self.yaw) + "\n Pitch: " + str(self.pitch) + "\n Roll: " + str(self.roll) + s = s + "\n quaternion: " + str(self.q) + "\n timeStamp: " + str(self.timeStamp) + "\n}" + return s + + +class ListenerPose3d(Node): + ''' + ROS Pose3D Subscriber. Pose3D Client to Receive pose3d from ROS nodes. + ''' + def __init__(self, topic): + ''' + ListenerPose3d Constructor. + + @param topic: ROS topic to subscribe + + @type topic: String + + ''' + super().__init__("pose3d_subscriber_node") + self.topic = topic + self.data = Pose3d() + self.sub = None + self.lock = threading.Lock() + self.start() + + def __callback (self, odom): + ''' + Callback function to receive and save Pose3d. + + @param odom: ROS Odometry received + + @type odom: Odometry + + ''' + pose = odometry2Pose3D(odom) + + + self.lock.acquire() + self.data = pose + self.lock.release() + + def stop(self): + ''' + Stops (Unregisters) the client. + + ''' + self.sub.unregister() + + def start (self): + ''' + Starts (Subscribes) the client. + + ''' + self.sub = self.create_subscription(nav_msgs.msg.Odometry, self.topic, self.__callback, 10) + + + def getPose3d(self): + ''' + Returns last Pose3d. + + @return last JdeRobotTypes Pose3d saved + + ''' + self.lock.acquire() + pose = self.data + self.lock.release() + + return pose + diff --git a/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/interfaces/pretrained_model/Readme.md b/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/interfaces/pretrained_model/Readme.md new file mode 100644 index 000000000..4841ae789 --- /dev/null +++ b/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/interfaces/pretrained_model/Readme.md @@ -0,0 +1 @@ +From Official Tensorflow Object Detection diff --git a/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/interfaces/pretrained_model/ssd_inception_v2_coco.pb b/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/interfaces/pretrained_model/ssd_inception_v2_coco.pb new file mode 100644 index 000000000..92189ed5f Binary files /dev/null and b/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/interfaces/pretrained_model/ssd_inception_v2_coco.pb differ diff --git a/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/interfaces/pretrained_model/ssd_inception_v2_coco.pbtxt b/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/interfaces/pretrained_model/ssd_inception_v2_coco.pbtxt new file mode 100644 index 000000000..4430041fb --- /dev/null +++ b/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/interfaces/pretrained_model/ssd_inception_v2_coco.pbtxt @@ -0,0 +1,2253 @@ +node { + name: "image_tensor" + op: "Placeholder" + attr { + key: "dtype" + value { + type: DT_UINT8 + } + } + attr { + key: "shape" + value { + shape { + dim { + size: -1 + } + dim { + size: -1 + } + dim { + size: -1 + } + dim { + size: 3 + } + } + } + } +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_0/BatchNorm/batchnorm/mul_1" + op: "Conv2D" + input: "image_tensor" + input: "FeatureExtractor/MobilenetV1/Conv2d_0/weights/read/_104__cf__107" + attr { + key: "padding" + value { + s: "SAME" + } + } + attr { + key: "strides" + value { + list { + i: 1 + i: 2 + i: 2 + i: 1 + } + } + } +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_0/BatchNorm/batchnorm/add_1" + op: "Add" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_0/BatchNorm/batchnorm/mul_1" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_0/BatchNorm/batchnorm/sub/_103__cf__106" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_0/Relu6" + op: "Relu6" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_0/BatchNorm/batchnorm/add_1" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_1_depthwise/depthwise" + op: "DepthwiseConv2dNative" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_0/Relu6" + input: "FeatureExtractor/MobilenetV1/Conv2d_1_depthwise/depthwise_weights/read/_101__cf__104" + attr { + key: "padding" + value { + s: "SAME" + } + } + attr { + key: "strides" + value { + list { + i: 1 + i: 1 + i: 1 + i: 1 + } + } + } +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_1_depthwise/BatchNorm/batchnorm/mul_1" + op: "Mul" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_1_depthwise/depthwise" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_1_depthwise/BatchNorm/batchnorm/mul/_99__cf__102" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_1_depthwise/BatchNorm/batchnorm/add_1" + op: "Add" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_1_depthwise/BatchNorm/batchnorm/mul_1" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_1_depthwise/BatchNorm/batchnorm/sub/_100__cf__103" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_1_depthwise/Relu6" + op: "Relu6" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_1_depthwise/BatchNorm/batchnorm/add_1" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_1_pointwise/BatchNorm/batchnorm/mul_1" + op: "Conv2D" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_1_depthwise/Relu6" + input: "FeatureExtractor/MobilenetV1/Conv2d_1_pointwise/weights/read/_98__cf__101" + attr { + key: "padding" + value { + s: "SAME" + } + } + attr { + key: "strides" + value { + list { + i: 1 + i: 1 + i: 1 + i: 1 + } + } + } +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_1_pointwise/BatchNorm/batchnorm/add_1" + op: "Add" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_1_pointwise/BatchNorm/batchnorm/mul_1" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_1_pointwise/BatchNorm/batchnorm/sub/_97__cf__100" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_1_pointwise/Relu6" + op: "Relu6" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_1_pointwise/BatchNorm/batchnorm/add_1" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_2_depthwise/depthwise" + op: "DepthwiseConv2dNative" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_1_pointwise/Relu6" + input: "FeatureExtractor/MobilenetV1/Conv2d_2_depthwise/depthwise_weights/read/_95__cf__98" + attr { + key: "padding" + value { + s: "SAME" + } + } + attr { + key: "strides" + value { + list { + i: 1 + i: 2 + i: 2 + i: 1 + } + } + } +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_2_depthwise/BatchNorm/batchnorm/mul_1" + op: "Mul" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_2_depthwise/depthwise" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_2_depthwise/BatchNorm/batchnorm/mul/_93__cf__96" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_2_depthwise/BatchNorm/batchnorm/add_1" + op: "Add" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_2_depthwise/BatchNorm/batchnorm/mul_1" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_2_depthwise/BatchNorm/batchnorm/sub/_94__cf__97" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_2_depthwise/Relu6" + op: "Relu6" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_2_depthwise/BatchNorm/batchnorm/add_1" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_2_pointwise/BatchNorm/batchnorm/mul_1" + op: "Conv2D" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_2_depthwise/Relu6" + input: "FeatureExtractor/MobilenetV1/Conv2d_2_pointwise/weights/read/_92__cf__95" + attr { + key: "padding" + value { + s: "SAME" + } + } + attr { + key: "strides" + value { + list { + i: 1 + i: 1 + i: 1 + i: 1 + } + } + } +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_2_pointwise/BatchNorm/batchnorm/add_1" + op: "Add" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_2_pointwise/BatchNorm/batchnorm/mul_1" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_2_pointwise/BatchNorm/batchnorm/sub/_91__cf__94" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_2_pointwise/Relu6" + op: "Relu6" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_2_pointwise/BatchNorm/batchnorm/add_1" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_3_depthwise/depthwise" + op: "DepthwiseConv2dNative" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_2_pointwise/Relu6" + input: "FeatureExtractor/MobilenetV1/Conv2d_3_depthwise/depthwise_weights/read/_89__cf__92" + attr { + key: "padding" + value { + s: "SAME" + } + } + attr { + key: "strides" + value { + list { + i: 1 + i: 1 + i: 1 + i: 1 + } + } + } +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_3_depthwise/BatchNorm/batchnorm/mul_1" + op: "Mul" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_3_depthwise/depthwise" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_3_depthwise/BatchNorm/batchnorm/mul/_87__cf__90" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_3_depthwise/BatchNorm/batchnorm/add_1" + op: "Add" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_3_depthwise/BatchNorm/batchnorm/mul_1" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_3_depthwise/BatchNorm/batchnorm/sub/_88__cf__91" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_3_depthwise/Relu6" + op: "Relu6" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_3_depthwise/BatchNorm/batchnorm/add_1" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_3_pointwise/BatchNorm/batchnorm/mul_1" + op: "Conv2D" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_3_depthwise/Relu6" + input: "FeatureExtractor/MobilenetV1/Conv2d_3_pointwise/weights/read/_86__cf__89" + attr { + key: "padding" + value { + s: "SAME" + } + } + attr { + key: "strides" + value { + list { + i: 1 + i: 1 + i: 1 + i: 1 + } + } + } +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_3_pointwise/BatchNorm/batchnorm/add_1" + op: "Add" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_3_pointwise/BatchNorm/batchnorm/mul_1" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_3_pointwise/BatchNorm/batchnorm/sub/_85__cf__88" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_3_pointwise/Relu6" + op: "Relu6" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_3_pointwise/BatchNorm/batchnorm/add_1" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_4_depthwise/depthwise" + op: "DepthwiseConv2dNative" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_3_pointwise/Relu6" + input: "FeatureExtractor/MobilenetV1/Conv2d_4_depthwise/depthwise_weights/read/_83__cf__86" + attr { + key: "padding" + value { + s: "SAME" + } + } + attr { + key: "strides" + value { + list { + i: 1 + i: 2 + i: 2 + i: 1 + } + } + } +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_4_depthwise/BatchNorm/batchnorm/mul_1" + op: "Mul" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_4_depthwise/depthwise" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_4_depthwise/BatchNorm/batchnorm/mul/_81__cf__84" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_4_depthwise/BatchNorm/batchnorm/add_1" + op: "Add" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_4_depthwise/BatchNorm/batchnorm/mul_1" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_4_depthwise/BatchNorm/batchnorm/sub/_82__cf__85" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_4_depthwise/Relu6" + op: "Relu6" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_4_depthwise/BatchNorm/batchnorm/add_1" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_4_pointwise/BatchNorm/batchnorm/mul_1" + op: "Conv2D" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_4_depthwise/Relu6" + input: "FeatureExtractor/MobilenetV1/Conv2d_4_pointwise/weights/read/_80__cf__83" + attr { + key: "padding" + value { + s: "SAME" + } + } + attr { + key: "strides" + value { + list { + i: 1 + i: 1 + i: 1 + i: 1 + } + } + } +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_4_pointwise/BatchNorm/batchnorm/add_1" + op: "Add" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_4_pointwise/BatchNorm/batchnorm/mul_1" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_4_pointwise/BatchNorm/batchnorm/sub/_79__cf__82" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_4_pointwise/Relu6" + op: "Relu6" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_4_pointwise/BatchNorm/batchnorm/add_1" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_5_depthwise/depthwise" + op: "DepthwiseConv2dNative" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_4_pointwise/Relu6" + input: "FeatureExtractor/MobilenetV1/Conv2d_5_depthwise/depthwise_weights/read/_77__cf__80" + attr { + key: "padding" + value { + s: "SAME" + } + } + attr { + key: "strides" + value { + list { + i: 1 + i: 1 + i: 1 + i: 1 + } + } + } +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_5_depthwise/BatchNorm/batchnorm/mul_1" + op: "Mul" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_5_depthwise/depthwise" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_5_depthwise/BatchNorm/batchnorm/mul/_75__cf__78" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_5_depthwise/BatchNorm/batchnorm/add_1" + op: "Add" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_5_depthwise/BatchNorm/batchnorm/mul_1" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_5_depthwise/BatchNorm/batchnorm/sub/_76__cf__79" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_5_depthwise/Relu6" + op: "Relu6" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_5_depthwise/BatchNorm/batchnorm/add_1" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_5_pointwise/BatchNorm/batchnorm/mul_1" + op: "Conv2D" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_5_depthwise/Relu6" + input: "FeatureExtractor/MobilenetV1/Conv2d_5_pointwise/weights/read/_74__cf__77" + attr { + key: "padding" + value { + s: "SAME" + } + } + attr { + key: "strides" + value { + list { + i: 1 + i: 1 + i: 1 + i: 1 + } + } + } +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_5_pointwise/BatchNorm/batchnorm/add_1" + op: "Add" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_5_pointwise/BatchNorm/batchnorm/mul_1" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_5_pointwise/BatchNorm/batchnorm/sub/_73__cf__76" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_5_pointwise/Relu6" + op: "Relu6" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_5_pointwise/BatchNorm/batchnorm/add_1" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_6_depthwise/depthwise" + op: "DepthwiseConv2dNative" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_5_pointwise/Relu6" + input: "FeatureExtractor/MobilenetV1/Conv2d_6_depthwise/depthwise_weights/read/_71__cf__74" + attr { + key: "padding" + value { + s: "SAME" + } + } + attr { + key: "strides" + value { + list { + i: 1 + i: 2 + i: 2 + i: 1 + } + } + } +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_6_depthwise/BatchNorm/batchnorm/mul_1" + op: "Mul" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_6_depthwise/depthwise" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_6_depthwise/BatchNorm/batchnorm/mul/_69__cf__72" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_6_depthwise/BatchNorm/batchnorm/add_1" + op: "Add" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_6_depthwise/BatchNorm/batchnorm/mul_1" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_6_depthwise/BatchNorm/batchnorm/sub/_70__cf__73" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_6_depthwise/Relu6" + op: "Relu6" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_6_depthwise/BatchNorm/batchnorm/add_1" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_6_pointwise/BatchNorm/batchnorm/mul_1" + op: "Conv2D" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_6_depthwise/Relu6" + input: "FeatureExtractor/MobilenetV1/Conv2d_6_pointwise/weights/read/_68__cf__71" + attr { + key: "padding" + value { + s: "SAME" + } + } + attr { + key: "strides" + value { + list { + i: 1 + i: 1 + i: 1 + i: 1 + } + } + } +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_6_pointwise/BatchNorm/batchnorm/add_1" + op: "Add" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_6_pointwise/BatchNorm/batchnorm/mul_1" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_6_pointwise/BatchNorm/batchnorm/sub/_67__cf__70" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_6_pointwise/Relu6" + op: "Relu6" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_6_pointwise/BatchNorm/batchnorm/add_1" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_7_depthwise/depthwise" + op: "DepthwiseConv2dNative" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_6_pointwise/Relu6" + input: "FeatureExtractor/MobilenetV1/Conv2d_7_depthwise/depthwise_weights/read/_65__cf__68" + attr { + key: "padding" + value { + s: "SAME" + } + } + attr { + key: "strides" + value { + list { + i: 1 + i: 1 + i: 1 + i: 1 + } + } + } +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_7_depthwise/BatchNorm/batchnorm/mul_1" + op: "Mul" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_7_depthwise/depthwise" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_7_depthwise/BatchNorm/batchnorm/mul/_63__cf__66" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_7_depthwise/BatchNorm/batchnorm/add_1" + op: "Add" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_7_depthwise/BatchNorm/batchnorm/mul_1" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_7_depthwise/BatchNorm/batchnorm/sub/_64__cf__67" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_7_depthwise/Relu6" + op: "Relu6" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_7_depthwise/BatchNorm/batchnorm/add_1" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_7_pointwise/BatchNorm/batchnorm/mul_1" + op: "Conv2D" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_7_depthwise/Relu6" + input: "FeatureExtractor/MobilenetV1/Conv2d_7_pointwise/weights/read/_62__cf__65" + attr { + key: "padding" + value { + s: "SAME" + } + } + attr { + key: "strides" + value { + list { + i: 1 + i: 1 + i: 1 + i: 1 + } + } + } +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_7_pointwise/BatchNorm/batchnorm/add_1" + op: "Add" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_7_pointwise/BatchNorm/batchnorm/mul_1" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_7_pointwise/BatchNorm/batchnorm/sub/_61__cf__64" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_7_pointwise/Relu6" + op: "Relu6" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_7_pointwise/BatchNorm/batchnorm/add_1" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_8_depthwise/depthwise" + op: "DepthwiseConv2dNative" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_7_pointwise/Relu6" + input: "FeatureExtractor/MobilenetV1/Conv2d_8_depthwise/depthwise_weights/read/_59__cf__62" + attr { + key: "padding" + value { + s: "SAME" + } + } + attr { + key: "strides" + value { + list { + i: 1 + i: 1 + i: 1 + i: 1 + } + } + } +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_8_depthwise/BatchNorm/batchnorm/mul_1" + op: "Mul" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_8_depthwise/depthwise" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_8_depthwise/BatchNorm/batchnorm/mul/_57__cf__60" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_8_depthwise/BatchNorm/batchnorm/add_1" + op: "Add" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_8_depthwise/BatchNorm/batchnorm/mul_1" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_8_depthwise/BatchNorm/batchnorm/sub/_58__cf__61" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_8_depthwise/Relu6" + op: "Relu6" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_8_depthwise/BatchNorm/batchnorm/add_1" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_8_pointwise/BatchNorm/batchnorm/mul_1" + op: "Conv2D" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_8_depthwise/Relu6" + input: "FeatureExtractor/MobilenetV1/Conv2d_8_pointwise/weights/read/_56__cf__59" + attr { + key: "padding" + value { + s: "SAME" + } + } + attr { + key: "strides" + value { + list { + i: 1 + i: 1 + i: 1 + i: 1 + } + } + } +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_8_pointwise/BatchNorm/batchnorm/add_1" + op: "Add" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_8_pointwise/BatchNorm/batchnorm/mul_1" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_8_pointwise/BatchNorm/batchnorm/sub/_55__cf__58" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_8_pointwise/Relu6" + op: "Relu6" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_8_pointwise/BatchNorm/batchnorm/add_1" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_9_depthwise/depthwise" + op: "DepthwiseConv2dNative" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_8_pointwise/Relu6" + input: "FeatureExtractor/MobilenetV1/Conv2d_9_depthwise/depthwise_weights/read/_53__cf__56" + attr { + key: "padding" + value { + s: "SAME" + } + } + attr { + key: "strides" + value { + list { + i: 1 + i: 1 + i: 1 + i: 1 + } + } + } +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_9_depthwise/BatchNorm/batchnorm/mul_1" + op: "Mul" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_9_depthwise/depthwise" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_9_depthwise/BatchNorm/batchnorm/mul/_51__cf__54" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_9_depthwise/BatchNorm/batchnorm/add_1" + op: "Add" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_9_depthwise/BatchNorm/batchnorm/mul_1" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_9_depthwise/BatchNorm/batchnorm/sub/_52__cf__55" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_9_depthwise/Relu6" + op: "Relu6" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_9_depthwise/BatchNorm/batchnorm/add_1" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_9_pointwise/BatchNorm/batchnorm/mul_1" + op: "Conv2D" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_9_depthwise/Relu6" + input: "FeatureExtractor/MobilenetV1/Conv2d_9_pointwise/weights/read/_50__cf__53" + attr { + key: "padding" + value { + s: "SAME" + } + } + attr { + key: "strides" + value { + list { + i: 1 + i: 1 + i: 1 + i: 1 + } + } + } +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_9_pointwise/BatchNorm/batchnorm/add_1" + op: "Add" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_9_pointwise/BatchNorm/batchnorm/mul_1" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_9_pointwise/BatchNorm/batchnorm/sub/_49__cf__52" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_9_pointwise/Relu6" + op: "Relu6" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_9_pointwise/BatchNorm/batchnorm/add_1" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_10_depthwise/depthwise" + op: "DepthwiseConv2dNative" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_9_pointwise/Relu6" + input: "FeatureExtractor/MobilenetV1/Conv2d_10_depthwise/depthwise_weights/read/_47__cf__50" + attr { + key: "padding" + value { + s: "SAME" + } + } + attr { + key: "strides" + value { + list { + i: 1 + i: 1 + i: 1 + i: 1 + } + } + } +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_10_depthwise/BatchNorm/batchnorm/mul_1" + op: "Mul" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_10_depthwise/depthwise" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_10_depthwise/BatchNorm/batchnorm/mul/_45__cf__48" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_10_depthwise/BatchNorm/batchnorm/add_1" + op: "Add" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_10_depthwise/BatchNorm/batchnorm/mul_1" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_10_depthwise/BatchNorm/batchnorm/sub/_46__cf__49" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_10_depthwise/Relu6" + op: "Relu6" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_10_depthwise/BatchNorm/batchnorm/add_1" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_10_pointwise/BatchNorm/batchnorm/mul_1" + op: "Conv2D" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_10_depthwise/Relu6" + input: "FeatureExtractor/MobilenetV1/Conv2d_10_pointwise/weights/read/_44__cf__47" + attr { + key: "padding" + value { + s: "SAME" + } + } + attr { + key: "strides" + value { + list { + i: 1 + i: 1 + i: 1 + i: 1 + } + } + } +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_10_pointwise/BatchNorm/batchnorm/add_1" + op: "Add" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_10_pointwise/BatchNorm/batchnorm/mul_1" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_10_pointwise/BatchNorm/batchnorm/sub/_43__cf__46" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_10_pointwise/Relu6" + op: "Relu6" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_10_pointwise/BatchNorm/batchnorm/add_1" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_11_depthwise/depthwise" + op: "DepthwiseConv2dNative" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_10_pointwise/Relu6" + input: "FeatureExtractor/MobilenetV1/Conv2d_11_depthwise/depthwise_weights/read/_41__cf__44" + attr { + key: "padding" + value { + s: "SAME" + } + } + attr { + key: "strides" + value { + list { + i: 1 + i: 1 + i: 1 + i: 1 + } + } + } +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_11_depthwise/BatchNorm/batchnorm/mul_1" + op: "Mul" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_11_depthwise/depthwise" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_11_depthwise/BatchNorm/batchnorm/mul/_39__cf__42" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_11_depthwise/BatchNorm/batchnorm/add_1" + op: "Add" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_11_depthwise/BatchNorm/batchnorm/mul_1" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_11_depthwise/BatchNorm/batchnorm/sub/_40__cf__43" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_11_depthwise/Relu6" + op: "Relu6" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_11_depthwise/BatchNorm/batchnorm/add_1" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_11_pointwise/BatchNorm/batchnorm/mul_1" + op: "Conv2D" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_11_depthwise/Relu6" + input: "FeatureExtractor/MobilenetV1/Conv2d_11_pointwise/weights/read/_38__cf__41" + attr { + key: "padding" + value { + s: "SAME" + } + } + attr { + key: "strides" + value { + list { + i: 1 + i: 1 + i: 1 + i: 1 + } + } + } +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_11_pointwise/BatchNorm/batchnorm/add_1" + op: "Add" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_11_pointwise/BatchNorm/batchnorm/mul_1" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_11_pointwise/BatchNorm/batchnorm/sub/_37__cf__40" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_11_pointwise/Relu6" + op: "Relu6" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_11_pointwise/BatchNorm/batchnorm/add_1" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_12_depthwise/depthwise" + op: "DepthwiseConv2dNative" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_11_pointwise/Relu6" + input: "FeatureExtractor/MobilenetV1/Conv2d_12_depthwise/depthwise_weights/read/_35__cf__38" + attr { + key: "padding" + value { + s: "SAME" + } + } + attr { + key: "strides" + value { + list { + i: 1 + i: 2 + i: 2 + i: 1 + } + } + } +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_12_depthwise/BatchNorm/batchnorm/mul_1" + op: "Mul" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_12_depthwise/depthwise" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_12_depthwise/BatchNorm/batchnorm/mul/_33__cf__36" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_12_depthwise/BatchNorm/batchnorm/add_1" + op: "Add" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_12_depthwise/BatchNorm/batchnorm/mul_1" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_12_depthwise/BatchNorm/batchnorm/sub/_34__cf__37" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_12_depthwise/Relu6" + op: "Relu6" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_12_depthwise/BatchNorm/batchnorm/add_1" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_12_pointwise/BatchNorm/batchnorm/mul_1" + op: "Conv2D" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_12_depthwise/Relu6" + input: "FeatureExtractor/MobilenetV1/Conv2d_12_pointwise/weights/read/_32__cf__35" + attr { + key: "padding" + value { + s: "SAME" + } + } + attr { + key: "strides" + value { + list { + i: 1 + i: 1 + i: 1 + i: 1 + } + } + } +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_12_pointwise/BatchNorm/batchnorm/add_1" + op: "Add" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_12_pointwise/BatchNorm/batchnorm/mul_1" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_12_pointwise/BatchNorm/batchnorm/sub/_31__cf__34" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_12_pointwise/Relu6" + op: "Relu6" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_12_pointwise/BatchNorm/batchnorm/add_1" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_13_depthwise/depthwise" + op: "DepthwiseConv2dNative" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_12_pointwise/Relu6" + input: "FeatureExtractor/MobilenetV1/Conv2d_13_depthwise/depthwise_weights/read/_29__cf__32" + attr { + key: "padding" + value { + s: "SAME" + } + } + attr { + key: "strides" + value { + list { + i: 1 + i: 1 + i: 1 + i: 1 + } + } + } +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_13_depthwise/BatchNorm/batchnorm/mul_1" + op: "Mul" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_13_depthwise/depthwise" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_13_depthwise/BatchNorm/batchnorm/mul/_27__cf__30" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_13_depthwise/BatchNorm/batchnorm/add_1" + op: "Add" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_13_depthwise/BatchNorm/batchnorm/mul_1" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_13_depthwise/BatchNorm/batchnorm/sub/_28__cf__31" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_13_depthwise/Relu6" + op: "Relu6" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_13_depthwise/BatchNorm/batchnorm/add_1" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_13_pointwise/BatchNorm/batchnorm/mul_1" + op: "Conv2D" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_13_depthwise/Relu6" + input: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise/weights/read/_26__cf__29" + attr { + key: "padding" + value { + s: "SAME" + } + } + attr { + key: "strides" + value { + list { + i: 1 + i: 1 + i: 1 + i: 1 + } + } + } +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_13_pointwise/BatchNorm/batchnorm/add_1" + op: "Add" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_13_pointwise/BatchNorm/batchnorm/mul_1" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_13_pointwise/BatchNorm/batchnorm/sub/_25__cf__28" +} +node { + name: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_13_pointwise/Relu6" + op: "Relu6" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_13_pointwise/BatchNorm/batchnorm/add_1" +} +node { + name: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_1_Conv2d_2_1x1_256/BatchNorm/batchnorm/mul_1" + op: "Conv2D" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_13_pointwise/Relu6" + input: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_1_Conv2d_2_1x1_256/weights/read/_23__cf__26" + attr { + key: "padding" + value { + s: "SAME" + } + } + attr { + key: "strides" + value { + list { + i: 1 + i: 1 + i: 1 + i: 1 + } + } + } +} +node { + name: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_1_Conv2d_2_1x1_256/BatchNorm/batchnorm/add_1" + op: "Add" + input: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_1_Conv2d_2_1x1_256/BatchNorm/batchnorm/mul_1" + input: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_1_Conv2d_2_1x1_256/BatchNorm/batchnorm/sub/_22__cf__25" +} +node { + name: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_1_Conv2d_2_1x1_256/Relu6" + op: "Relu6" + input: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_1_Conv2d_2_1x1_256/BatchNorm/batchnorm/add_1" +} +node { + name: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_2_Conv2d_2_3x3_s2_512/BatchNorm/batchnorm/mul_1" + op: "Conv2D" + input: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_1_Conv2d_2_1x1_256/Relu6" + input: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_2_Conv2d_2_3x3_s2_512/weights/read/_20__cf__23" + attr { + key: "padding" + value { + s: "SAME" + } + } + attr { + key: "strides" + value { + list { + i: 1 + i: 2 + i: 2 + i: 1 + } + } + } +} +node { + name: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_2_Conv2d_2_3x3_s2_512/BatchNorm/batchnorm/add_1" + op: "Add" + input: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_2_Conv2d_2_3x3_s2_512/BatchNorm/batchnorm/mul_1" + input: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_2_Conv2d_2_3x3_s2_512/BatchNorm/batchnorm/sub/_19__cf__22" +} +node { + name: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_2_Conv2d_2_3x3_s2_512/Relu6" + op: "Relu6" + input: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_2_Conv2d_2_3x3_s2_512/BatchNorm/batchnorm/add_1" +} +node { + name: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_1_Conv2d_3_1x1_128/BatchNorm/batchnorm/mul_1" + op: "Conv2D" + input: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_2_Conv2d_2_3x3_s2_512/Relu6" + input: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_1_Conv2d_3_1x1_128/weights/read/_17__cf__20" + attr { + key: "padding" + value { + s: "SAME" + } + } + attr { + key: "strides" + value { + list { + i: 1 + i: 1 + i: 1 + i: 1 + } + } + } +} +node { + name: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_1_Conv2d_3_1x1_128/BatchNorm/batchnorm/add_1" + op: "Add" + input: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_1_Conv2d_3_1x1_128/BatchNorm/batchnorm/mul_1" + input: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_1_Conv2d_3_1x1_128/BatchNorm/batchnorm/sub/_16__cf__19" +} +node { + name: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_1_Conv2d_3_1x1_128/Relu6" + op: "Relu6" + input: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_1_Conv2d_3_1x1_128/BatchNorm/batchnorm/add_1" +} +node { + name: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_2_Conv2d_3_3x3_s2_256/BatchNorm/batchnorm/mul_1" + op: "Conv2D" + input: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_1_Conv2d_3_1x1_128/Relu6" + input: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_2_Conv2d_3_3x3_s2_256/weights/read/_14__cf__17" + attr { + key: "padding" + value { + s: "SAME" + } + } + attr { + key: "strides" + value { + list { + i: 1 + i: 2 + i: 2 + i: 1 + } + } + } +} +node { + name: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_2_Conv2d_3_3x3_s2_256/BatchNorm/batchnorm/add_1" + op: "Add" + input: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_2_Conv2d_3_3x3_s2_256/BatchNorm/batchnorm/mul_1" + input: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_2_Conv2d_3_3x3_s2_256/BatchNorm/batchnorm/sub/_13__cf__16" +} +node { + name: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_2_Conv2d_3_3x3_s2_256/Relu6" + op: "Relu6" + input: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_2_Conv2d_3_3x3_s2_256/BatchNorm/batchnorm/add_1" +} +node { + name: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_1_Conv2d_4_1x1_128/BatchNorm/batchnorm/mul_1" + op: "Conv2D" + input: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_2_Conv2d_3_3x3_s2_256/Relu6" + input: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_1_Conv2d_4_1x1_128/weights/read/_11__cf__14" + attr { + key: "padding" + value { + s: "SAME" + } + } + attr { + key: "strides" + value { + list { + i: 1 + i: 1 + i: 1 + i: 1 + } + } + } +} +node { + name: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_1_Conv2d_4_1x1_128/BatchNorm/batchnorm/add_1" + op: "Add" + input: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_1_Conv2d_4_1x1_128/BatchNorm/batchnorm/mul_1" + input: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_1_Conv2d_4_1x1_128/BatchNorm/batchnorm/sub/_10__cf__13" +} +node { + name: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_1_Conv2d_4_1x1_128/Relu6" + op: "Relu6" + input: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_1_Conv2d_4_1x1_128/BatchNorm/batchnorm/add_1" +} +node { + name: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_2_Conv2d_4_3x3_s2_256/BatchNorm/batchnorm/mul_1" + op: "Conv2D" + input: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_1_Conv2d_4_1x1_128/Relu6" + input: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_2_Conv2d_4_3x3_s2_256/weights/read/_8__cf__11" + attr { + key: "padding" + value { + s: "SAME" + } + } + attr { + key: "strides" + value { + list { + i: 1 + i: 2 + i: 2 + i: 1 + } + } + } +} +node { + name: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_2_Conv2d_4_3x3_s2_256/BatchNorm/batchnorm/add_1" + op: "Add" + input: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_2_Conv2d_4_3x3_s2_256/BatchNorm/batchnorm/mul_1" + input: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_2_Conv2d_4_3x3_s2_256/BatchNorm/batchnorm/sub/_7__cf__10" +} +node { + name: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_2_Conv2d_4_3x3_s2_256/Relu6" + op: "Relu6" + input: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_2_Conv2d_4_3x3_s2_256/BatchNorm/batchnorm/add_1" +} +node { + name: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_1_Conv2d_5_1x1_64/BatchNorm/batchnorm/mul_1" + op: "Conv2D" + input: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_2_Conv2d_4_3x3_s2_256/Relu6" + input: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_1_Conv2d_5_1x1_64/weights/read/_5__cf__8" + attr { + key: "padding" + value { + s: "SAME" + } + } + attr { + key: "strides" + value { + list { + i: 1 + i: 1 + i: 1 + i: 1 + } + } + } +} +node { + name: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_1_Conv2d_5_1x1_64/BatchNorm/batchnorm/add_1" + op: "Add" + input: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_1_Conv2d_5_1x1_64/BatchNorm/batchnorm/mul_1" + input: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_1_Conv2d_5_1x1_64/BatchNorm/batchnorm/sub/_4__cf__7" +} +node { + name: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_1_Conv2d_5_1x1_64/Relu6" + op: "Relu6" + input: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_1_Conv2d_5_1x1_64/BatchNorm/batchnorm/add_1" +} +node { + name: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_2_Conv2d_5_3x3_s2_128/BatchNorm/batchnorm/mul_1" + op: "Conv2D" + input: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_1_Conv2d_5_1x1_64/Relu6" + input: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_2_Conv2d_5_3x3_s2_128/weights/read/_2__cf__5" + attr { + key: "padding" + value { + s: "SAME" + } + } + attr { + key: "strides" + value { + list { + i: 1 + i: 2 + i: 2 + i: 1 + } + } + } +} +node { + name: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_2_Conv2d_5_3x3_s2_128/BatchNorm/batchnorm/add_1" + op: "Add" + input: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_2_Conv2d_5_3x3_s2_128/BatchNorm/batchnorm/mul_1" + input: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_2_Conv2d_5_3x3_s2_128/BatchNorm/batchnorm/sub/_1__cf__4" +} +node { + name: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_2_Conv2d_5_3x3_s2_128/Relu6" + op: "Relu6" + input: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_2_Conv2d_5_3x3_s2_128/BatchNorm/batchnorm/add_1" +} +node { + name: "BoxPredictor_5/BoxEncodingPredictor/Conv2D" + op: "Conv2D" + input: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_2_Conv2d_5_3x3_s2_128/Relu6" + input: "BoxPredictor_5/BoxEncodingPredictor/weights/read/_106__cf__109" + attr { + key: "padding" + value { + s: "SAME" + } + } + attr { + key: "strides" + value { + list { + i: 1 + i: 1 + i: 1 + i: 1 + } + } + } +} +node { + name: "BoxPredictor_5/BoxEncodingPredictor/BiasAdd" + op: "BiasAdd" + input: "BoxPredictor_5/BoxEncodingPredictor/Conv2D" + input: "BoxPredictor_5/BoxEncodingPredictor/biases/read/_105__cf__108" +} +node { + name: "BoxPredictor_5/ClassPredictor/Conv2D" + op: "Conv2D" + input: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_2_Conv2d_5_3x3_s2_128/Relu6" + input: "BoxPredictor_5/ClassPredictor/weights/read/_168__cf__171" + attr { + key: "padding" + value { + s: "SAME" + } + } + attr { + key: "strides" + value { + list { + i: 1 + i: 1 + i: 1 + i: 1 + } + } + } +} +node { + name: "BoxPredictor_5/ClassPredictor/BiasAdd" + op: "BiasAdd" + input: "BoxPredictor_5/ClassPredictor/Conv2D" + input: "BoxPredictor_5/ClassPredictor/biases/read/_167__cf__170" +} +node { + name: "BoxPredictor_4/BoxEncodingPredictor/Conv2D" + op: "Conv2D" + input: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_2_Conv2d_4_3x3_s2_256/Relu6" + input: "BoxPredictor_4/BoxEncodingPredictor/weights/read/_108__cf__111" + attr { + key: "padding" + value { + s: "SAME" + } + } + attr { + key: "strides" + value { + list { + i: 1 + i: 1 + i: 1 + i: 1 + } + } + } +} +node { + name: "BoxPredictor_4/BoxEncodingPredictor/BiasAdd" + op: "BiasAdd" + input: "BoxPredictor_4/BoxEncodingPredictor/Conv2D" + input: "BoxPredictor_4/BoxEncodingPredictor/biases/read/_107__cf__110" +} +node { + name: "BoxPredictor_4/ClassPredictor/Conv2D" + op: "Conv2D" + input: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_2_Conv2d_4_3x3_s2_256/Relu6" + input: "BoxPredictor_4/ClassPredictor/weights/read/_170__cf__173" + attr { + key: "padding" + value { + s: "SAME" + } + } + attr { + key: "strides" + value { + list { + i: 1 + i: 1 + i: 1 + i: 1 + } + } + } +} +node { + name: "BoxPredictor_4/ClassPredictor/BiasAdd" + op: "BiasAdd" + input: "BoxPredictor_4/ClassPredictor/Conv2D" + input: "BoxPredictor_4/ClassPredictor/biases/read/_169__cf__172" +} +node { + name: "BoxPredictor_3/BoxEncodingPredictor/Conv2D" + op: "Conv2D" + input: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_2_Conv2d_3_3x3_s2_256/Relu6" + input: "BoxPredictor_3/BoxEncodingPredictor/weights/read/_110__cf__113" + attr { + key: "padding" + value { + s: "SAME" + } + } + attr { + key: "strides" + value { + list { + i: 1 + i: 1 + i: 1 + i: 1 + } + } + } +} +node { + name: "BoxPredictor_3/BoxEncodingPredictor/BiasAdd" + op: "BiasAdd" + input: "BoxPredictor_3/BoxEncodingPredictor/Conv2D" + input: "BoxPredictor_3/BoxEncodingPredictor/biases/read/_109__cf__112" +} +node { + name: "BoxPredictor_3/ClassPredictor/Conv2D" + op: "Conv2D" + input: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_2_Conv2d_3_3x3_s2_256/Relu6" + input: "BoxPredictor_3/ClassPredictor/weights/read/_172__cf__175" + attr { + key: "padding" + value { + s: "SAME" + } + } + attr { + key: "strides" + value { + list { + i: 1 + i: 1 + i: 1 + i: 1 + } + } + } +} +node { + name: "BoxPredictor_3/ClassPredictor/BiasAdd" + op: "BiasAdd" + input: "BoxPredictor_3/ClassPredictor/Conv2D" + input: "BoxPredictor_3/ClassPredictor/biases/read/_171__cf__174" +} +node { + name: "BoxPredictor_2/BoxEncodingPredictor/Conv2D" + op: "Conv2D" + input: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_2_Conv2d_2_3x3_s2_512/Relu6" + input: "BoxPredictor_2/BoxEncodingPredictor/weights/read/_112__cf__115" + attr { + key: "padding" + value { + s: "SAME" + } + } + attr { + key: "strides" + value { + list { + i: 1 + i: 1 + i: 1 + i: 1 + } + } + } +} +node { + name: "BoxPredictor_2/BoxEncodingPredictor/BiasAdd" + op: "BiasAdd" + input: "BoxPredictor_2/BoxEncodingPredictor/Conv2D" + input: "BoxPredictor_2/BoxEncodingPredictor/biases/read/_111__cf__114" +} +node { + name: "BoxPredictor_2/ClassPredictor/Conv2D" + op: "Conv2D" + input: "FeatureExtractor/MobilenetV1/Conv2d_13_pointwise_2_Conv2d_2_3x3_s2_512/Relu6" + input: "BoxPredictor_2/ClassPredictor/weights/read/_174__cf__177" + attr { + key: "padding" + value { + s: "SAME" + } + } + attr { + key: "strides" + value { + list { + i: 1 + i: 1 + i: 1 + i: 1 + } + } + } +} +node { + name: "BoxPredictor_2/ClassPredictor/BiasAdd" + op: "BiasAdd" + input: "BoxPredictor_2/ClassPredictor/Conv2D" + input: "BoxPredictor_2/ClassPredictor/biases/read/_173__cf__176" +} +node { + name: "BoxPredictor_1/BoxEncodingPredictor/Conv2D" + op: "Conv2D" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_13_pointwise/Relu6" + input: "BoxPredictor_1/BoxEncodingPredictor/weights/read/_114__cf__117" + attr { + key: "padding" + value { + s: "SAME" + } + } + attr { + key: "strides" + value { + list { + i: 1 + i: 1 + i: 1 + i: 1 + } + } + } +} +node { + name: "BoxPredictor_1/BoxEncodingPredictor/BiasAdd" + op: "BiasAdd" + input: "BoxPredictor_1/BoxEncodingPredictor/Conv2D" + input: "BoxPredictor_1/BoxEncodingPredictor/biases/read/_113__cf__116" +} +node { + name: "BoxPredictor_1/ClassPredictor/Conv2D" + op: "Conv2D" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_13_pointwise/Relu6" + input: "BoxPredictor_1/ClassPredictor/weights/read/_176__cf__179" + attr { + key: "padding" + value { + s: "SAME" + } + } + attr { + key: "strides" + value { + list { + i: 1 + i: 1 + i: 1 + i: 1 + } + } + } +} +node { + name: "BoxPredictor_1/ClassPredictor/BiasAdd" + op: "BiasAdd" + input: "BoxPredictor_1/ClassPredictor/Conv2D" + input: "BoxPredictor_1/ClassPredictor/biases/read/_175__cf__178" +} +node { + name: "BoxPredictor_0/BoxEncodingPredictor/Conv2D" + op: "Conv2D" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_11_pointwise/Relu6" + input: "BoxPredictor_0/BoxEncodingPredictor/weights/read/_116__cf__119" + attr { + key: "padding" + value { + s: "SAME" + } + } + attr { + key: "strides" + value { + list { + i: 1 + i: 1 + i: 1 + i: 1 + } + } + } +} +node { + name: "BoxPredictor_0/BoxEncodingPredictor/BiasAdd" + op: "BiasAdd" + input: "BoxPredictor_0/BoxEncodingPredictor/Conv2D" + input: "BoxPredictor_0/BoxEncodingPredictor/biases/read/_115__cf__118" +} +node { + name: "BoxPredictor_0/ClassPredictor/Conv2D" + op: "Conv2D" + input: "FeatureExtractor/MobilenetV1/MobilenetV1/Conv2d_11_pointwise/Relu6" + input: "BoxPredictor_0/ClassPredictor/weights/read/_178__cf__181" + attr { + key: "padding" + value { + s: "SAME" + } + } + attr { + key: "strides" + value { + list { + i: 1 + i: 1 + i: 1 + i: 1 + } + } + } +} +node { + name: "BoxPredictor_0/ClassPredictor/BiasAdd" + op: "BiasAdd" + input: "BoxPredictor_0/ClassPredictor/Conv2D" + input: "BoxPredictor_0/ClassPredictor/biases/read/_177__cf__180" +} +node { + name: "concat/axis_flatten" + op: "Const" + attr { + key: "value" + value { + tensor { + dtype: DT_INT32 + tensor_shape { + } + int_val: -1 + } + } + } +} +node { + name: "BoxPredictor_0/ClassPredictor/BiasAdd/Flatten" + op: "Flatten" + input: "BoxPredictor_0/ClassPredictor/BiasAdd" +} +node { + name: "BoxPredictor_1/ClassPredictor/BiasAdd/Flatten" + op: "Flatten" + input: "BoxPredictor_1/ClassPredictor/BiasAdd" +} +node { + name: "BoxPredictor_2/ClassPredictor/BiasAdd/Flatten" + op: "Flatten" + input: "BoxPredictor_2/ClassPredictor/BiasAdd" +} +node { + name: "BoxPredictor_3/ClassPredictor/BiasAdd/Flatten" + op: "Flatten" + input: "BoxPredictor_3/ClassPredictor/BiasAdd" +} +node { + name: "BoxPredictor_4/ClassPredictor/BiasAdd/Flatten" + op: "Flatten" + input: "BoxPredictor_4/ClassPredictor/BiasAdd" +} +node { + name: "BoxPredictor_5/ClassPredictor/BiasAdd/Flatten" + op: "Flatten" + input: "BoxPredictor_5/ClassPredictor/BiasAdd" +} +node { + name: "ClassPredictor/concat" + op: "ConcatV2" + input: "BoxPredictor_0/ClassPredictor/BiasAdd/Flatten" + input: "BoxPredictor_1/ClassPredictor/BiasAdd/Flatten" + input: "BoxPredictor_2/ClassPredictor/BiasAdd/Flatten" + input: "BoxPredictor_3/ClassPredictor/BiasAdd/Flatten" + input: "BoxPredictor_4/ClassPredictor/BiasAdd/Flatten" + input: "BoxPredictor_5/ClassPredictor/BiasAdd/Flatten" + input: "concat/axis_flatten" +} +node { + name: "BoxPredictor_0/BoxEncodingPredictor/BiasAdd/Flatten" + op: "Flatten" + input: "BoxPredictor_0/BoxEncodingPredictor/BiasAdd" +} +node { + name: "BoxPredictor_1/BoxEncodingPredictor/BiasAdd/Flatten" + op: "Flatten" + input: "BoxPredictor_1/BoxEncodingPredictor/BiasAdd" +} +node { + name: "BoxPredictor_2/BoxEncodingPredictor/BiasAdd/Flatten" + op: "Flatten" + input: "BoxPredictor_2/BoxEncodingPredictor/BiasAdd" +} +node { + name: "BoxPredictor_3/BoxEncodingPredictor/BiasAdd/Flatten" + op: "Flatten" + input: "BoxPredictor_3/BoxEncodingPredictor/BiasAdd" +} +node { + name: "BoxPredictor_4/BoxEncodingPredictor/BiasAdd/Flatten" + op: "Flatten" + input: "BoxPredictor_4/BoxEncodingPredictor/BiasAdd" +} +node { + name: "BoxPredictor_5/BoxEncodingPredictor/BiasAdd/Flatten" + op: "Flatten" + input: "BoxPredictor_5/BoxEncodingPredictor/BiasAdd" +} +node { + name: "BoxEncodingPredictor/concat" + op: "ConcatV2" + input: "BoxPredictor_0/BoxEncodingPredictor/BiasAdd/Flatten" + input: "BoxPredictor_1/BoxEncodingPredictor/BiasAdd/Flatten" + input: "BoxPredictor_2/BoxEncodingPredictor/BiasAdd/Flatten" + input: "BoxPredictor_3/BoxEncodingPredictor/BiasAdd/Flatten" + input: "BoxPredictor_4/BoxEncodingPredictor/BiasAdd/Flatten" + input: "BoxPredictor_5/BoxEncodingPredictor/BiasAdd/Flatten" + input: "concat/axis_flatten" +} +node { + name: "PriorBox_0" + op: "PriorBox" + input: "BoxPredictor_0/BoxEncodingPredictor/BiasAdd" + input: "image_tensor" + attr { + key: "clip" + value { + b: false + } + } + attr { + key: "flip" + value { + b: false + } + } + attr { + key: "height" + value { + tensor { + dtype: DT_FLOAT + tensor_shape { + dim { + size: 3 + } + } + float_val: 30.0 + float_val: 42.4264068604 + float_val: 84.8528137207 + } + } + } + attr { + key: "variance" + value { + tensor { + dtype: DT_FLOAT + tensor_shape { + dim { + size: 4 + } + } + float_val: 0.10000000149 + float_val: 0.10000000149 + float_val: 0.20000000298 + float_val: 0.20000000298 + } + } + } + attr { + key: "width" + value { + tensor { + dtype: DT_FLOAT + tensor_shape { + dim { + size: 3 + } + } + float_val: 30.0 + float_val: 84.8528137207 + float_val: 42.4264068604 + } + } + } +} +node { + name: "PriorBox_1" + op: "PriorBox" + input: "BoxPredictor_1/BoxEncodingPredictor/BiasAdd" + input: "image_tensor" + attr { + key: "clip" + value { + b: false + } + } + attr { + key: "flip" + value { + b: false + } + } + attr { + key: "height" + value { + tensor { + dtype: DT_FLOAT + tensor_shape { + dim { + size: 6 + } + } + float_val: 105.0 + float_val: 74.2462081909 + float_val: 148.492416382 + float_val: 60.6217765808 + float_val: 181.956329346 + float_val: 125.499000549 + } + } + } + attr { + key: "variance" + value { + tensor { + dtype: DT_FLOAT + tensor_shape { + dim { + size: 4 + } + } + float_val: 0.10000000149 + float_val: 0.10000000149 + float_val: 0.20000000298 + float_val: 0.20000000298 + } + } + } + attr { + key: "width" + value { + tensor { + dtype: DT_FLOAT + tensor_shape { + dim { + size: 6 + } + } + float_val: 105.0 + float_val: 148.492416382 + float_val: 74.2462081909 + float_val: 181.865341187 + float_val: 60.5914611816 + float_val: 125.499000549 + } + } + } +} +node { + name: "PriorBox_2" + op: "PriorBox" + input: "BoxPredictor_2/BoxEncodingPredictor/BiasAdd" + input: "image_tensor" + attr { + key: "clip" + value { + b: false + } + } + attr { + key: "flip" + value { + b: false + } + } + attr { + key: "height" + value { + tensor { + dtype: DT_FLOAT + tensor_shape { + dim { + size: 6 + } + } + float_val: 150.0 + float_val: 106.066017151 + float_val: 212.132034302 + float_val: 86.6025390625 + float_val: 259.93762207 + float_val: 171.026321411 + } + } + } + attr { + key: "variance" + value { + tensor { + dtype: DT_FLOAT + tensor_shape { + dim { + size: 4 + } + } + float_val: 0.10000000149 + float_val: 0.10000000149 + float_val: 0.20000000298 + float_val: 0.20000000298 + } + } + } + attr { + key: "width" + value { + tensor { + dtype: DT_FLOAT + tensor_shape { + dim { + size: 6 + } + } + float_val: 150.0 + float_val: 212.132034302 + float_val: 106.066017151 + float_val: 259.807617188 + float_val: 86.5592269897 + float_val: 171.026321411 + } + } + } +} +node { + name: "PriorBox_3" + op: "PriorBox" + input: "BoxPredictor_3/BoxEncodingPredictor/BiasAdd" + input: "image_tensor" + attr { + key: "clip" + value { + b: false + } + } + attr { + key: "flip" + value { + b: false + } + } + attr { + key: "height" + value { + tensor { + dtype: DT_FLOAT + tensor_shape { + dim { + size: 6 + } + } + float_val: 195.0 + float_val: 137.885818481 + float_val: 275.771636963 + float_val: 112.583305359 + float_val: 337.918914795 + float_val: 216.333084106 + } + } + } + attr { + key: "variance" + value { + tensor { + dtype: DT_FLOAT + tensor_shape { + dim { + size: 4 + } + } + float_val: 0.10000000149 + float_val: 0.10000000149 + float_val: 0.20000000298 + float_val: 0.20000000298 + } + } + } + attr { + key: "width" + value { + tensor { + dtype: DT_FLOAT + tensor_shape { + dim { + size: 6 + } + } + float_val: 195.0 + float_val: 275.771636963 + float_val: 137.885818481 + float_val: 337.749908447 + float_val: 112.527000427 + float_val: 216.333084106 + } + } + } +} +node { + name: "PriorBox_4" + op: "PriorBox" + input: "BoxPredictor_4/BoxEncodingPredictor/BiasAdd" + input: "image_tensor" + attr { + key: "clip" + value { + b: false + } + } + attr { + key: "flip" + value { + b: false + } + } + attr { + key: "height" + value { + tensor { + dtype: DT_FLOAT + tensor_shape { + dim { + size: 6 + } + } + float_val: 240.0 + float_val: 169.705627441 + float_val: 339.411254883 + float_val: 138.564071655 + float_val: 415.90020752 + float_val: 261.533935547 + } + } + } + attr { + key: "variance" + value { + tensor { + dtype: DT_FLOAT + tensor_shape { + dim { + size: 4 + } + } + float_val: 0.10000000149 + float_val: 0.10000000149 + float_val: 0.20000000298 + float_val: 0.20000000298 + } + } + } + attr { + key: "width" + value { + tensor { + dtype: DT_FLOAT + tensor_shape { + dim { + size: 6 + } + } + float_val: 240.0 + float_val: 339.411254883 + float_val: 169.705627441 + float_val: 415.692199707 + float_val: 138.494766235 + float_val: 261.533935547 + } + } + } +} +node { + name: "PriorBox_5" + op: "PriorBox" + input: "BoxPredictor_5/BoxEncodingPredictor/BiasAdd" + input: "image_tensor" + attr { + key: "clip" + value { + b: false + } + } + attr { + key: "flip" + value { + b: false + } + } + attr { + key: "height" + value { + tensor { + dtype: DT_FLOAT + tensor_shape { + dim { + size: 6 + } + } + float_val: 285.0 + float_val: 201.525436401 + float_val: 403.050872803 + float_val: 164.544830322 + float_val: 493.881469727 + float_val: 292.403839111 + } + } + } + attr { + key: "variance" + value { + tensor { + dtype: DT_FLOAT + tensor_shape { + dim { + size: 4 + } + } + float_val: 0.10000000149 + float_val: 0.10000000149 + float_val: 0.20000000298 + float_val: 0.20000000298 + } + } + } + attr { + key: "width" + value { + tensor { + dtype: DT_FLOAT + tensor_shape { + dim { + size: 6 + } + } + float_val: 285.0 + float_val: 403.050872803 + float_val: 201.525436401 + float_val: 493.634490967 + float_val: 164.462539673 + float_val: 292.403839111 + } + } + } +} +node { + name: "PriorBox/concat" + op: "ConcatV2" + input: "PriorBox_0" + input: "PriorBox_1" + input: "PriorBox_2" + input: "PriorBox_3" + input: "PriorBox_4" + input: "PriorBox_5" + input: "concat/axis_flatten" +} +node { + name: "ClassPredictor/concat/sigmoid" + op: "Sigmoid" + input: "ClassPredictor/concat" +} +node { + name: "detection_out" + op: "DetectionOutput" + input: "BoxEncodingPredictor/concat" + input: "ClassPredictor/concat/sigmoid" + input: "PriorBox/concat" + attr { + key: "background_label_id" + value { + i: 0 + } + } + attr { + key: "code_type" + value { + s: "CENTER_SIZE" + } + } + attr { + key: "confidence_threshold" + value { + f: 0.00999999977648 + } + } + attr { + key: "keep_top_k" + value { + i: 100 + } + } + attr { + key: "loc_pred_transposed" + value { + b: true + } + } + attr { + key: "nms_threshold" + value { + f: 0.600000023842 + } + } + attr { + key: "num_classes" + value { + i: 91 + } + } + attr { + key: "share_location" + value { + b: true + } + } + attr { + key: "top_k" + value { + i: 100 + } + } +} +library { +} diff --git a/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/interfaces/ssd_detection.py b/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/interfaces/ssd_detection.py new file mode 100644 index 000000000..2dbd30d64 --- /dev/null +++ b/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/interfaces/ssd_detection.py @@ -0,0 +1,33 @@ +import cv2 + +FROZEN_GRAPH = "/RoboticsAcademy/exercises/static/exercises/follow_person_newmanager/python_template/ros2_humble/interfaces/pretrained_model/ssd_inception_v2_coco.pb" +PB_TXT = "/RoboticsAcademy/exercises/static/exercises/follow_person_newmanager/python_template/ros2_humble/interfaces/pretrained_model/ssd_inception_v2_coco.pbtxt" +SIZE = 300 + +class BoundingBox: + def __init__(self, identifier, class_id, score, xmin, ymin, xmax, ymax): + self.id = identifier + self.class_id = class_id + self.score = score + self.xmin = xmin + self.ymin = ymin + self.xmax = xmax + self.ymax = ymax + + def __str__(self): + s = "[id:{}\nclass:{}\nscore:{}\nxmin:{}\nymin:{}\nxmax:{}\nymax:{}\n".format( + self.id, self.class_id, self.score, self.xmin, self.ymin, self.xmax, self.ymax) + return s + +class NeuralNetwork: + + def __init__(self): + self.net = cv2.dnn.readNetFromTensorflow(FROZEN_GRAPH, PB_TXT) + + def detect(self, img): + rows = img.shape[0] + cols = img.shape[1] + self.net.setInput(cv2.dnn.blobFromImage(img, 1.0/127.5, (SIZE, SIZE), (127.5, 127.5, 127.5), swapRB=True, crop=False)) + cvOut = self.net.forward() + + return cvOut[0, 0, :, :] diff --git a/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/interfaces/threadPublisher.py b/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/interfaces/threadPublisher.py new file mode 100644 index 000000000..69aa0ad48 --- /dev/null +++ b/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/interfaces/threadPublisher.py @@ -0,0 +1,46 @@ +# +# Copyright (C) 1997-2016 JDE Developers Team +# +# This program is free software: you can redistribute it and/or modify +# it under the terms of the GNU General Public License as published by +# the Free Software Foundation, either version 3 of the License, or +# (at your option) any later version. +# +# This program is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY; without even the implied warranty of +# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +# GNU General Public License for more details. +# +# You should have received a copy of the GNU General Public License +# along with this program. If not, see http://www.gnu.org/licenses/. +# Authors : +# Alberto Martin Florido +# Aitor Martinez Fernandez +# +import threading +import time +from datetime import datetime + +time_cycle = 80 + + +class ThreadPublisher(threading.Thread): + + def __init__(self, pub, kill_event): + self.pub = pub + self.kill_event = kill_event + threading.Thread.__init__(self, args=kill_event) + + def run(self): + while (not self.kill_event.is_set()): + start_time = datetime.now() + + self.pub.publish() + + finish_Time = datetime.now() + + dt = finish_Time - start_time + ms = (dt.days * 24 * 60 * 60 + dt.seconds) * 1000 + dt.microseconds / 1000.0 + #print (ms) + if (ms < time_cycle): + time.sleep((time_cycle - ms) / 1000.0) \ No newline at end of file diff --git a/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/shared/__init__.py b/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/shared/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/shared/image.py b/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/shared/image.py new file mode 100644 index 000000000..87c700c8c --- /dev/null +++ b/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/shared/image.py @@ -0,0 +1,124 @@ +import traceback + +import numpy as np +import mmap +from posix_ipc import Semaphore, O_CREX, ExistentialError, O_CREAT, SharedMemory, unlink_shared_memory +from ctypes import sizeof, memmove, addressof, create_string_buffer +from shared.structure_img import MD + +# Probably, using self variables gives errors with memmove +# Therefore, a global variable for utility +md_buf = create_string_buffer(sizeof(MD)) + +class SharedImage: + def __init__(self, name): + # Initialize variables for memory regions and buffers and Semaphore + self.shm_buf = None; self.shm_region = None + self.md_buf = None; self.md_region = None + self.image_lock = None + + self.shm_name = name; self.md_name = name + "-meta" + self.image_lock_name = name + + # Initialize or retreive metadata memory region + try: + self.md_region = SharedMemory(self.md_name) + self.md_buf = mmap.mmap(self.md_region.fd, sizeof(MD)) + self.md_region.close_fd() + except ExistentialError: + self.md_region = SharedMemory(self.md_name, O_CREAT, size=sizeof(MD)) + self.md_buf = mmap.mmap(self.md_region.fd, self.md_region.size) + self.md_region.close_fd() + + # Initialize or retreive Semaphore + try: + self.image_lock = Semaphore(self.image_lock_name, O_CREX) + except ExistentialError: + image_lock = Semaphore(self.image_lock_name, O_CREAT) + image_lock.unlink() + self.image_lock = Semaphore(self.image_lock_name, O_CREX) + + self.image_lock.release() + + # Get the shared image + def get(self): + # Define metadata + metadata = MD() + + # Get metadata from the shared region + self.image_lock.acquire() + md_buf[:] = self.md_buf + memmove(addressof(metadata), md_buf, sizeof(metadata)) + # print(f"Shared memory metadata: {metadata}") + size = metadata.size + self.image_lock.release() + + # Try to retreive the image from shm_buffer + # Otherwise return a zero image + try: + # dmariaa70@gmail.com > With this change, error doesn't appear but screen is still black + # self.shm_region = SharedMemory(self.shm_name, size=size) + # print(f"Shared memory region size: {self.shm_region.size}") + self.shm_region = SharedMemory(self.shm_name) + self.shm_buf = mmap.mmap(self.shm_region.fd, size) + self.shm_region.close_fd() + + self.image_lock.acquire() + image = np.ndarray(shape=(metadata.shape_0, metadata.shape_1, metadata.shape_2), + dtype='uint8', buffer=self.shm_buf) + self.image_lock.release() + + # Check for a None image + if(image.size == 0): + image = np.zeros((3, 3, 3), np.uint8) + except ExistentialError: + image = np.zeros((3, 3, 3), np.uint8) + # dmariaa70@gmail.com + # when image size does not match expected size, we get an error + # on line 61 + except Exception as e: + # if self.shm_name == "halimage": + # print("halimage exception happened: ") + # print(e) + image = np.zeros((3, 3, 3), np.uint8) + + return image + + # Add the shared image + def add(self, image): + try: + # Get byte size of the image + byte_size = image.nbytes + + # Get the shared memory buffer to read from + if not self.shm_region: + self.shm_region = SharedMemory(self.shm_name, O_CREAT, size=byte_size) + self.shm_buf = mmap.mmap(self.shm_region.fd, byte_size) + self.shm_region.close_fd() + + # Generate meta data + metadata = MD(image.shape[0], image.shape[1], image.shape[2], byte_size) + + # Send the meta data and image to shared regions + self.image_lock.acquire() + memmove(md_buf, addressof(metadata), sizeof(metadata)) + self.md_buf[:] = md_buf[:] + self.shm_buf[:] = image.tobytes() + self.image_lock.release() + except Exception as e: + print(f"Error in shared image add {repr(e)}") + print(traceback.format_exc()) + + # Destructor function to unlink and disconnect + def close(self): + self.image_lock.acquire() + self.md_buf.close() + + try: + unlink_shared_memory(self.md_name) + unlink_shared_memory(self.shm_name) + except ExistentialError: + pass + + self.image_lock.release() + self.image_lock.close() diff --git a/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/shared/laserdata.py b/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/shared/laserdata.py new file mode 100644 index 000000000..914849087 --- /dev/null +++ b/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/shared/laserdata.py @@ -0,0 +1,65 @@ +import numpy as np +import mmap +from posix_ipc import Semaphore, O_CREX, ExistentialError, O_CREAT, SharedMemory, unlink_shared_memory +from ctypes import sizeof, c_float +import struct +import array + +class SharedLaserData: + def __init__(self, name): + # Initialize variables for memory regions and buffers and Semaphore + self.shm_buf = None; self.shm_region = None + self.laserdata_lock = None + + self.shm_name = name; + self.laserdata_lock_name = name + + # Initialize shared memory buffer + try: + self.shm_region = SharedMemory(self.shm_name) + self.shm_buf = mmap.mmap(self.shm_region.fd, sizeof(c_float)*360) + self.shm_region.close_fd() + except ExistentialError: + self.shm_region = SharedMemory(self.shm_name, O_CREAT, size=sizeof(c_float)*360) + self.shm_buf = mmap.mmap(self.shm_region.fd, self.shm_region.size) + self.shm_region.close_fd() + + # Initialize or retreive Semaphore + try: + self.laserdata_lock = Semaphore(self.laserdata_lock_name, O_CREX) + except ExistentialError: + laserdata_lock = Semaphore(self.laserdata_lock_name, O_CREAT) + laserdata_lock.unlink() + self.laserdata_lock = Semaphore(self.laserdata_lock_name, O_CREX) + + self.laserdata_lock.release() + + # Get the shared value + def get(self): + # Retreive the data from buffer + self.laserdata_lock.acquire() + laserdata_tuple = struct.unpack('360f', self.shm_buf) + laserdata = array.array('f', laserdata_tuple) + self.laserdata_lock.release() + + return laserdata + + # Add the shared value + def add(self, laserdata): + # Send the data to shared regions + self.laserdata_lock.acquire() + self.shm_buf[:] = laserdata + self.laserdata_lock.release() + + # Destructor function to unlink and disconnect + def close(self): + self.laserdata_lock.acquire() + self.shm_buf.close() + + try: + unlink_shared_memory(self.shm_name) + except ExistentialError: + pass + + self.laserdata_lock.release() + self.laserdata_lock.close() diff --git a/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/shared/pose3d.py b/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/shared/pose3d.py new file mode 100644 index 000000000..963b3d803 --- /dev/null +++ b/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/shared/pose3d.py @@ -0,0 +1,82 @@ +import numpy as np +import mmap +from posix_ipc import Semaphore, O_CREX, ExistentialError, O_CREAT, SharedMemory, unlink_shared_memory +from ctypes import sizeof, c_float +import struct + +# Auxiliary class to store position data (x, y, yaw) +class Pose(): + def __init__(self): + self.x = 0.0 # X coord [meters] + self.y = 0.0 # Y coord [meters] + self.yaw = 0.0 #Yaw angle[rads] + + def __str__(self): + s = "Pose3D: {\n x: " + str(self.x) + "\n y: " + str(self.y) + "\n Yaw: " + str(self.yaw) + "\n}" + return s + +class SharedPose3D: + def __init__(self, name): + # Initialize variables for memory regions and buffers and Semaphore + self.shm_buf = None + self.shm_region = None + self.pose_lock = None + + self.shm_name = name + self.pose_lock_name = name + + self.pose = Pose() + + # Initialize shared memory buffer + try: + self.shm_region = SharedMemory(self.shm_name) + self.shm_buf = mmap.mmap(self.shm_region.fd, sizeof(c_float)*3) + self.shm_region.close_fd() + except ExistentialError: + self.shm_region = SharedMemory(self.shm_name, O_CREAT, size=sizeof(c_float)*3) + self.shm_buf = mmap.mmap(self.shm_region.fd, self.shm_region.size) + self.shm_region.close_fd() + + # Initialize or retreive Semaphore + try: + self.pose_lock = Semaphore(self.pose_lock_name, O_CREX) + except ExistentialError: + pose_lock = Semaphore(self.pose_lock_name, O_CREAT) + pose_lock.unlink() + self.pose_lock = Semaphore(self.pose_lock_name, O_CREX) + + self.pose_lock.release() + + # Get the shared value + def get(self): + # Retreive the data from buffer + self.pose_lock.acquire() + pose_tuple = struct.unpack('3f', self.shm_buf) + self.pose_lock.release() + + pose = Pose() + pose.x = pose_tuple[0] + pose.y = pose_tuple[1] + pose.yaw = pose_tuple[2] + + return pose + + # Add the shared value + def add(self, pose): + # Send the data to shared regions + self.pose_lock.acquire() + self.shm_buf[:] = struct.pack('3f', pose.x, pose.y, pose.yaw) + self.pose_lock.release() + + # Destructor function to unlink and disconnect + def close(self): + self.pose_lock.acquire() + self.shm_buf.close() + + try: + unlink_shared_memory(self.shm_name) + except ExistentialError: + pass + + self.pose_lock.release() + self.pose_lock.close() diff --git a/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/shared/structure_img.py b/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/shared/structure_img.py new file mode 100644 index 000000000..ed79cd96f --- /dev/null +++ b/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/shared/structure_img.py @@ -0,0 +1,18 @@ +from ctypes import Structure, c_int32, c_int64 + + +class MD(Structure): + _fields_ = [ + ('shape_0', c_int32), + ('shape_1', c_int32), + ('shape_2', c_int32), + ('size', c_int64) + ] + + def __str__(self): + return f"---- MD -----\n" \ + f" shape_0: {self.shape_0}\n" \ + f" shape_1: {self.shape_1}\n" \ + f" shape_2: {self.shape_2}\n" \ + f" size: {self.size}\n" \ + f"-------------" diff --git a/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/shared/value.py b/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/shared/value.py new file mode 100644 index 000000000..4007e929c --- /dev/null +++ b/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/shared/value.py @@ -0,0 +1,63 @@ +import numpy as np +import mmap +from posix_ipc import Semaphore, O_CREX, ExistentialError, O_CREAT, SharedMemory, unlink_shared_memory +from ctypes import sizeof, memmove, addressof, create_string_buffer, c_float +import struct + +class SharedValue: + def __init__(self, name): + # Initialize variables for memory regions and buffers and Semaphore + self.shm_buf = None; self.shm_region = None + self.value_lock = None + + self.shm_name = name; + self.value_lock_name = name + + # Initialize shared memory buffer + try: + self.shm_region = SharedMemory(self.shm_name) + self.shm_buf = mmap.mmap(self.shm_region.fd, sizeof(c_float)) + self.shm_region.close_fd() + except ExistentialError: + self.shm_region = SharedMemory(self.shm_name, O_CREAT, size=sizeof(c_float)) + self.shm_buf = mmap.mmap(self.shm_region.fd, self.shm_region.size) + self.shm_region.close_fd() + + # Initialize or retreive Semaphore + try: + self.value_lock = Semaphore(self.value_lock_name, O_CREX) + except ExistentialError: + value_lock = Semaphore(self.value_lock_name, O_CREAT) + value_lock.unlink() + self.value_lock = Semaphore(self.value_lock_name, O_CREX) + + self.value_lock.release() + + # Get the shared value + def get(self): + # Retreive the data from buffer + self.value_lock.acquire() + value = struct.unpack('f', self.shm_buf)[0] + self.value_lock.release() + + return value + + # Add the shared value + def add(self, value): + # Send the data to shared regions + self.value_lock.acquire() + self.shm_buf[:] = struct.pack('f', value) + self.value_lock.release() + + # Destructor function to unlink and disconnect + def close(self): + self.value_lock.acquire() + self.shm_buf.close() + + try: + unlink_shared_memory(self.shm_name) + except ExistentialError: + pass + + self.value_lock.release() + self.value_lock.close() diff --git a/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/user_functions.py b/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/user_functions.py new file mode 100644 index 000000000..0f994c698 --- /dev/null +++ b/exercises/static/exercises/real_follow_person_newmanager/python_template/ros2_humble/user_functions.py @@ -0,0 +1,75 @@ +from shared.image import SharedImage +from shared.value import SharedValue +from shared.laserdata import SharedLaserData +from shared.pose3d import SharedPose3D + +from interfaces.ssd_detection import NeuralNetwork, BoundingBox +from coco_labels import LABEL_MAP + +import cv2 + +# Define HAL functions +class HALFunctions: + def __init__(self): + # Initialize image variable + self.shared_image = SharedImage("halimage") + self.shared_v = SharedValue("velocity") + self.shared_w = SharedValue("angular") + self.shared_laserdata = SharedLaserData("laserdata") + self.shared_pose = SharedPose3D("pose") + + self.net = NeuralNetwork() + + # Get pose function (x, y , yaw) + def getPose3d(self): + pose = self.shared_pose.get() + return pose + + # Get laser data function + def getLaserData(self): + data = self.shared_laserdata.get() + return data + + # Get bounding boxes function + def getBoundingBoxes(self, img): + rows = img.shape[0] + cols = img.shape[1] + detections = self.net.detect(img) + bounding_boxes = [] + for detection in detections: + bounding_box = BoundingBox( + int(detection[1]), + LABEL_MAP[int(detection[1])], + float(detection[2]), + detection[3]*cols, + detection[4]*rows, + detection[5]*cols, + detection[6]*rows) + bounding_boxes.append(bounding_box) + return bounding_boxes + + # Get image function + def getImage(self): + image = self.shared_image.get() + return image + + # Send velocity function + def sendV(self, velocity): + self.shared_v.add(velocity) + + # Send angular velocity function + def sendW(self, angular): + self.shared_w.add(angular) + +# Define GUI functions +class GUIFunctions: + def __init__(self): + # Initialize image variable + self.shared_image = SharedImage("guiimage") + + # Show image function + def showImage(self, image): + # Reshape to 3 channel if it has only 1 in order to display it + if (len(image.shape) < 3): + image = cv2.cvtColor(image, cv2.COLOR_GRAY2RGB) + self.shared_image.add(image) \ No newline at end of file diff --git a/exercises/static/exercises/real_follow_person_newmanager/react-components/MapSelector.js b/exercises/static/exercises/real_follow_person_newmanager/react-components/MapSelector.js new file mode 100644 index 000000000..a22ab8579 --- /dev/null +++ b/exercises/static/exercises/real_follow_person_newmanager/react-components/MapSelector.js @@ -0,0 +1,118 @@ +import React, { useEffect, useState } from "react"; + +import MenuItem from "@mui/material/MenuItem"; +import LandscapeIcon from "@mui/icons-material/Landscape"; + +import { FormControl, InputLabel, Select, Box } from "@mui/material"; + +const serverBase = `${document.location.protocol}//${document.location.hostname}:8000`; +const exerciseConfig = JSON.parse( + document.getElementById("exercise-config").textContent +); +const exerciseId = exerciseConfig.exercise_id; + +export default function MapSelector(props) { + const changeConfig = (circuitPath) => { + const config = JSON.parse( + document.getElementById("exercise-config").textContent + ); + config.application.params = { circuit: circuitPath }; + config.launch[ + "0" + ].launch_file = `$EXERCISE_FOLDER/launch/simple_line_follower_ros_headless_${circuitPath}.launch`; + return config; + }; + + const handleCircuitChange = (e) => { + const config = e; + console.log(JSON.stringify(config)); + config['exercise_id'] = exerciseId; + config.height = window.innerHeight / 2; + config.width = window.innerWidth / 2; + window.RoboticsExerciseComponents.commsManager.terminate().then(() => { + window.RoboticsExerciseComponents.commsManager.launch(config); + }); + }; + + const [disabled, setDisabled] = useState(true); + const [circuitOptions, setCircuitOptions] = useState([]); + + useEffect(() => { + const callback = (message) => { + if (message.data.state === "ready") { + setDisabled(false); + } else { + setDisabled(true); + } + }; + window.RoboticsExerciseComponents.commsManager.subscribe( + [window.RoboticsExerciseComponents.commsManager.events.STATE_CHANGED], + callback + ); + + return () => { + window.RoboticsExerciseComponents.commsManager.unsubscribe( + [window.RoboticsExerciseComponents.commsManager.events.STATE_CHANGED], + callback + ); + }; + }, []); + + useEffect(() => { + const mapsAvailableURL = `${serverBase}/exercises/exercise/${exerciseId}/launch_files`; + fetch(mapsAvailableURL) + .then((response) => response.json()) + .then((data) => { + const rosVersionURL = `${serverBase}/exercises/ros_version/`; + let ros_version = 1; + fetch(rosVersionURL) + .then((res) => res.json()) + .then((msg) => { + ros_version = msg.version; + // If returns no version, assume 1 + if (isNaN(parseInt(ros_version))) { + ros_version = 1; + } + const config = data; + // Selects the configs available for the ROS version installed + const availableConfigs = {}; + availableConfigs[`ROS${ros_version}`] = config[`ROS${ros_version}`]; + setCircuitOptions(availableConfigs[`ROS${ros_version}`]); + }) + .catch((error) => { + const availableConfigs = {}; + availableConfigs[`ROS${ros_version}`] = config[`ROS${ros_version}`]; + setCircuitOptions(availableConfigs[`ROS${ros_version}`]); + }) + }) + .catch((error) => { + console.log("Error fetching circuit options:", error); + }); + }, []); + + return ( + + + + + + + + + ); +} diff --git a/exercises/static/exercises/real_follow_person_newmanager/react-components/RealFollowPersonRR.js b/exercises/static/exercises/real_follow_person_newmanager/react-components/RealFollowPersonRR.js new file mode 100644 index 000000000..204d67254 --- /dev/null +++ b/exercises/static/exercises/real_follow_person_newmanager/react-components/RealFollowPersonRR.js @@ -0,0 +1,14 @@ +import * as React from "react"; +import {Fragment} from "react"; + +import "./css/RealFollowPersonRR.css"; + +const RealFollowPersonRR = (props) => { + return ( + + {props.children} + + ); +}; + +export default RealFollowPersonRR; \ No newline at end of file diff --git a/exercises/static/exercises/real_follow_person_newmanager/react-components/css/RealFollowPersonRR.css b/exercises/static/exercises/real_follow_person_newmanager/react-components/css/RealFollowPersonRR.css new file mode 100644 index 000000000..3bdee7925 --- /dev/null +++ b/exercises/static/exercises/real_follow_person_newmanager/react-components/css/RealFollowPersonRR.css @@ -0,0 +1,28 @@ +* { + box-sizing: border-box; +} + +body, html { + width: 100%; height: 100%; +} + +#exercise-container { + position: absolute; + top: 0; left: 0; bottom: 0; right: 0; + overflow: hidden; + display: flex; + flex-direction: column; +} + +#exercise-container #content { + width: 100%; + height: 100%; + overflow: hidden; +} + +#exercise-container #content #content-exercise { + display: flex; + flex-direction: column; + width: 100%; + height: 100%; +} \ No newline at end of file diff --git a/exercises/templates/exercise_base.html b/exercises/templates/exercise_base.html index d68eea154..de431dbf9 100644 --- a/exercises/templates/exercise_base.html +++ b/exercises/templates/exercise_base.html @@ -613,4 +613,4 @@ {% include "info_modal.html" %} {% include "load_modal.html" %} - + \ No newline at end of file diff --git a/exercises/templates/exercises/real_follow_person_newmanager/exercise.html b/exercises/templates/exercises/real_follow_person_newmanager/exercise.html new file mode 100644 index 000000000..f4d50cc1f --- /dev/null +++ b/exercises/templates/exercises/real_follow_person_newmanager/exercise.html @@ -0,0 +1,35 @@ +{% extends "react_frontend/exercise_base.html" %} +{% load react_component %} + +{% block exercise_header %} +{% endblock %} + +{% block react-content %} + {% react_component exercise/real_follow_person_newmanager/RealFollowPersonRR %} + + {% react_component components/wrappers/MaterialBox id="exercise-container" %} + {% react_component components/layout_components/MainAppBar exerciseName="Real Follow Person RR" %} + {% react_component exercise/real_follow_person_newmanager/MapSelector %} {% end_react_component %} + {% end_react_component %} + {% react_component components/wrappers/MaterialBox id="content" %} + {% react_component components/wrappers/MaterialBox id="content-exercise" %} + {% react_component components/layout_components/ExerciseControl %}{% end_react_component %} + {% react_component components/wrappers/FlexContainer row %} + {% react_component components/wrappers/FlexContainer%} + {% react_component components/editors/AceEditorRobot %}{% end_react_component %} + {% react_component components/visualizers/ConsoleViewer%}{% end_react_component %} + {% end_react_component%} + {% react_component components/wrappers/FlexContainer%} + {% react_component exercise/real_follow_person_newmanager/ImgCanvas %}{% end_react_component %} + {% react_component components/visualizers/GazeboViewer%}{% end_react_component %} + {% end_react_component %} + {% end_react_component %} + {% end_react_component %} +{% react_component components/views/TheoryView url="https://jderobot.github.io/RoboticsAcademy/exercises/MobileRobots/real_follow_person/" %}{% end_react_component %} +{% react_component components/views/ForumView %}{% end_react_component %} + {% react_component components/message_system/Loading %}{% end_react_component %} + {% react_component components/message_system/Alert %}{% end_react_component %} +{% end_react_component %} +{% end_react_component %} + {% end_react_component %} +{% endblock %} \ No newline at end of file diff --git a/exercises/urls.py b/exercises/urls.py index 50952eda8..9903bad8b 100644 --- a/exercises/urls.py +++ b/exercises/urls.py @@ -9,4 +9,4 @@ path('evaluate_style/', views.evaluate_style, name="evaluate_style"), path('ros_version/', views.ros_version, name='ros_version'), path("exercise//launch_files", views.launch_files, name='launch_files') -] +] \ No newline at end of file diff --git a/exercises/views.py b/exercises/views.py index fbf177b8b..d10ec9fa0 100644 --- a/exercises/views.py +++ b/exercises/views.py @@ -97,4 +97,4 @@ def request_code(request, exercise_id): if difficulty is not None: print('EXERCISE: ', exercise_id, 'DIFFICULTY: ', difficulty) - return HttpResponse(data, content_type="text/plain") + return HttpResponse(data, content_type="text/plain") \ No newline at end of file diff --git a/manager/manager.py b/manager/manager.py index b4dfa36a3..bbeb120ae 100644 --- a/manager/manager.py +++ b/manager/manager.py @@ -802,4 +802,4 @@ def run_server(self): if __name__ == "__main__": server = Manager() - server.run_server() + server.run_server() \ No newline at end of file diff --git a/scripts/mini_RADI/Dockerfile.dependencies_humble b/scripts/mini_RADI/Dockerfile.dependencies_humble index 36bf8c9ea..b67ae6f84 100644 --- a/scripts/mini_RADI/Dockerfile.dependencies_humble +++ b/scripts/mini_RADI/Dockerfile.dependencies_humble @@ -137,7 +137,7 @@ ENV PATH "$PATH:/opt/VirtualGL/bin:/opt/TurboVNC/bin" RUN curl -sL https://deb.nodesource.com/setup_16.x | bash - \ && apt-get install -y nodejs \ && npm install -g yarn - + # Install Python 3 pip build dependencies first RUN python3.10 -m pip install --upgrade pip wheel setuptools @@ -152,6 +152,23 @@ RUN python3.10 -m pip install \ RUN python3.10 -m pip install websocket_server posix-ipc django==4.1.7 djangorestframework==3.13.1 \ django-webpack-loader==1.5.0 django-cors-headers==3.14.0 websockets asyncio +# Dependecies for exercise Real Follow Person +RUN add-apt-repository universe +RUN apt-get update && apt-get install -y \ + ros-${ROS_DISTRO}-usb-cam \ + ros-${ROS_DISTRO}-ecl-* \ + ros-${ROS_DISTRO}-pcl-* \ + ros-${ROS_DISTRO}-kobuki-* \ + ros-${ROS_DISTRO}-diagnostic-updater \ + ros-${ROS_DISTRO}-rosidl-* \ + ros-${ROS_DISTRO}-ros-core \ + ros-${ROS_DISTRO}-ament-cmake \ + ftdi-eeprom \ + libusb-dev \ + libftdi-dev \ + && rm -rf /var/lib/apt/lists/* + + # PX4 pip installs RUN python3.10 -m pip install jsonschema pymavlink pyserial diff --git a/scripts/mini_RADI/Dockerfile.mini_humble b/scripts/mini_RADI/Dockerfile.mini_humble index e9887cf0f..975759f57 100644 --- a/scripts/mini_RADI/Dockerfile.mini_humble +++ b/scripts/mini_RADI/Dockerfile.mini_humble @@ -5,7 +5,7 @@ WORKDIR / # RoboticsInfrasctructure Repository ARG ROBOTICS_INFRASTRUCTURE=$ROBOTICS_INFRASTRUCTURE RUN mkdir -p /opt/jderobot && \ - git clone https://github.com/JdeRobot/RoboticsInfraestructure.git -b $ROBOTICS_INFRASTRUCTURE /opt/jderobot + git clone https://github.com/JdeRobot/RoboticsInfrastructure.git -b $ROBOTICS_INFRASTRUCTURE /opt/jderobot # create workspace and add Robot packages RUN mkdir -p /home/ws/src @@ -19,6 +19,31 @@ WORKDIR /home/ws RUN rosdep install --from-paths src --ignore-src -r --rosdistro humble -y RUN /bin/bash -c "source /opt/ros/humble/setup.bash; colcon build --symlink-install" +# create workspace and add physical robot packages +RUN mkdir -p /home/ws2/src +RUN cp -r /opt/jderobot/CustomRobots/Turtlebot2/Turtlebot2_physical /home/ws2/src + + +####################### Real Follow Person Exercise ################################### +# Clone rplidar and kobuki repositories +WORKDIR /home/ws2/src/Turtlebot2_physical +RUN vcs import . < rplidar_instructions/repos +RUN vcs import . < kobuki_instructions/repos +RUN touch /home/ws2/src/Turtlebot2_physical/kobuki_ros_iterfaces/COLCON_IGNORE + +# Compile workspace +WORKDIR /home/ws2 +RUN rosdep install --from-paths src --ignore-src -r --rosdistro humble -y +RUN colcon build --symlink-install + +# udev rules for kobuki base and rplidar +RUN cp /home/ws2/src/Turtlebot2_physical/kobuki_ftdi/60-kobuki.rules /etc/udev/rules.d +RUN cp /home/ws2/src/Turtlebot2_physical/rplidar_ros/scripts/rplidar.rules /etc/udev/rules.d +WORKDIR /home/ws2/src/Turtlebot2_physical/rplidar_ros/scripts +RUN ./create_udev_rules.sh +########################################################################################### + + # Clone the RoboticsApplicationManager repository into the src folder inside RoboticsAcademy ARG RAM=$RAM RUN git clone https://github.com/JdeRobot/RoboticsApplicationManager.git -b $RAM /RoboticsApplicationManager