diff --git a/common/hal_interfaces/hal_interfaces/general/lidar.py b/common/hal_interfaces/hal_interfaces/general/lidar.py new file mode 100644 index 000000000..315c3c45b --- /dev/null +++ b/common/hal_interfaces/hal_interfaces/general/lidar.py @@ -0,0 +1,89 @@ +from rclpy.node import Node +import sensor_msgs.msg +from math import pi as PI + + +### AUXILIARY FUNCTIONS +class LidarData: + + def __init__(self): + + self.values = [] # Actual point data, size is (row_step*height) + + # 2D structure of the point cloud. If the cloud is unordered, height is + # 1 and width is the length of the point cloud. + self.height = 0 + self.width = 0 + + self.point_step = 0 # Length of a point in bytes + self.row_step = 0 # Length of a row in bytes + self.fields = [] # Describes the channels and their layout in the binary data blob. + self.is_dense = False # True if there are no invalid points + self.timeStamp = 0 # seconds + + def __str__(self): + s = ( + "LidarData: {\n height: " + + str(self.height) + + "\n width: " + + str(self.width) + ) + s = ( + s + + "\n point_step: " + + str(self.point_step) + + "\n row_step: " + + str(self.row_step) + ) + s = ( + s + + "\n fields: " + + str(self.fields) + + "\n is_dense: " + + str(self.is_dense) + ) + s = ( + s + + "\n timeStamp: " + + str(self.timeStamp) + + "\n values: " + + str(self.values) + + "\n}" + ) + return s + + +def lidarScan2LidarData(scan): + """ + Translates from ROS LidarScan to JderobotTypes LidarData. + @param scan: ROS LidarScan to translate + @type scan: LidarScan + @return a LidarData translated from scan + """ + lidar = LidarData() + lidar.values = scan.data + lidar.height = scan.height + lidar.width = scan.width + lidar.point_step = scan.point_step + lidar.row_step = scan.row_step + lidar.fields = scan.fields + lidar.is_dense = scan.is_dense + lidar.timeStamp = scan.header.stamp.sec + (scan.header.stamp.nanosec * 1e-9) + return lidar + + +### HAL INTERFACE ### +class LidarNode(Node): + + def __init__(self, topic): + super().__init__("lidar_node") + self.sub = self.create_subscription( + sensor_msgs.msg.PointCloud2, topic, self.listener_callback, 10 + ) + self.last_scan_ = sensor_msgs.msg.PointCloud2() + + def listener_callback(self, scan): + self.last_scan_ = scan + + def getLidarData(self): + return lidarScan2LidarData(self.last_scan_) diff --git a/common/hal_interfaces/hal_interfaces/specific/threed_reconstruction/parameters_camera.py b/common/hal_interfaces/hal_interfaces/specific/threed_reconstruction/parameters_camera.py index 01b830618..b42cea801 100644 --- a/common/hal_interfaces/hal_interfaces/specific/threed_reconstruction/parameters_camera.py +++ b/common/hal_interfaces/hal_interfaces/specific/threed_reconstruction/parameters_camera.py @@ -7,7 +7,7 @@ def __init__(self, configFile, cam): if os.getcwd() == "/": f = open( - "/RoboticsAcademy/exercises/static/exercises/3d_reconstruction_newmanager/python_template/ros2_humble/" + configFile, "r") + "/RoboticsAcademy/exercises/static/exercises/3d_reconstruction/python_template/ros2_humble/" + configFile, "r") else: f = open(configFile, "r") diff --git a/database/exercises/db.sql b/database/exercises/db.sql index dd8d6b194..cc2c1a587 100644 --- a/database/exercises/db.sql +++ b/database/exercises/db.sql @@ -95,6 +95,7 @@ COPY public.exercises (id, exercise_id, name, description, tags, status, templat 9 3d_reconstruction 3D Reconstruction 3D Reconstruction exercise using React and RAM {"tags": ["ROS2","COMPUTER VISION"]} ACTIVE RoboticsAcademy/exercises/static/exercises/3d_reconstruction/python_template/ 10 amazon_warehouse Amazon Warehouse Control an amazon-like robot to organize a warehouse {"tags": "ROS2"} ACTIVE RoboticsAcademy/exercises/static/exercises/amazon_warehouse/python_template/ 11 montecarlo_laser_loc Montecarlo Laser Loc Calculate the position of the robot based on the {"tags": "ROS2"} ACTIVE RoboticsAcademy/exercises/static/exercises/montecarlo_laser_loc/python_template/ +12 autoparking_lidar Autoparking with Lidar Autoparking with Lidar exercise {"tags": ["AUTONOMOUS DRIVING","SERVICE ROBOTS","ROS2"] } ACTIVE RoboticsAcademy/exercises/static/exercises/autoparking_lidar/python_template/ \. @@ -129,6 +130,7 @@ COPY public.exercises_universes (id, exercise_id, universe_id) FROM stdin; 24 1 23 25 1 24 26 1 25 +27 12 26 \. diff --git a/exercises/static/exercises/assets/img/autoparking_lidar_teaser.png b/exercises/static/exercises/assets/img/autoparking_lidar_teaser.png new file mode 100644 index 000000000..b65037a16 Binary files /dev/null and b/exercises/static/exercises/assets/img/autoparking_lidar_teaser.png differ diff --git a/exercises/static/exercises/autoparking_lidar/python_template/ros2_humble/GUI.py b/exercises/static/exercises/autoparking_lidar/python_template/ros2_humble/GUI.py new file mode 100755 index 000000000..0f49db390 --- /dev/null +++ b/exercises/static/exercises/autoparking_lidar/python_template/ros2_humble/GUI.py @@ -0,0 +1,38 @@ +import json + +from gui_interfaces.general.measuring_threading_gui import MeasuringThreadingGUI +from console_interfaces.general.console import start_console +from map import Map +from HAL import getLidarData + +# Graphical User Interface Class + +class GUI(MeasuringThreadingGUI): + + def __init__(self, host="ws://127.0.0.1:2303"): + super().__init__(host) + + # Payload vars + self.payload = {'map': ''} + self.map = Map(getLidarData) + + self.start() + + # Prepares and sends a map to the websocket server + def update_gui(self): + + map_message = self.map.get_json_data() + self.payload["map"] = map_message + message = json.dumps(self.payload) + self.send_to_client(message) + + + def reset_gui(self): + """Resets the GUI to its initial state.""" + self.map.reset() + +host = "ws://127.0.0.1:2303" +gui = GUI(host) + +# Redirect the console +start_console() diff --git a/exercises/static/exercises/autoparking_lidar/python_template/ros2_humble/HAL.py b/exercises/static/exercises/autoparking_lidar/python_template/ros2_humble/HAL.py new file mode 100755 index 000000000..bf0964ea0 --- /dev/null +++ b/exercises/static/exercises/autoparking_lidar/python_template/ros2_humble/HAL.py @@ -0,0 +1,52 @@ +import rclpy +import threading +import time + +from hal_interfaces.general.motors import MotorsNode +from hal_interfaces.general.odometry import OdometryNode +from hal_interfaces.general.lidar import LidarNode + +# Hardware Abstraction Layer +IMG_WIDTH = 320 +IMG_HEIGHT = 240 +freq = 30.0 + +# ROS2 init + +print("HAL initializing", flush=True) +if not rclpy.ok(): + rclpy.init(args=None) + + ### HAL INIT ### + motor_node = MotorsNode("/prius_autoparking/cmd_vel", 4, 0.3) + odometry_node = OdometryNode("/prius_autoparking/odom") + lidar_node = LidarNode("/prius_autoparking/cloud") + + # Spin nodes so that subscription callbacks load topic data + executor = rclpy.executors.MultiThreadedExecutor() + executor.add_node(odometry_node) + executor.add_node(lidar_node) + def __auto_spin() -> None: + while rclpy.ok(): + executor.spin_once(timeout_sec=0) + time.sleep(1/freq) + executor_thread = threading.Thread(target=__auto_spin, daemon=True) + executor_thread.start() + + +def getPose3d(): + return odometry_node.getPose3d() + +def getLidarData(): + lidar = lidar_node.getLidarData() + timestamp = lidar.timeStamp + while timestamp == 0.0: + lidar = lidar_node.getLidarData() + timestamp = lidar.timeStamp + return lidar + +def setV(velocity): + motor_node.sendV(float(velocity)) + +def setW(velocity): + motor_node.sendW(float(velocity)) \ No newline at end of file diff --git a/exercises/static/exercises/autoparking_lidar/python_template/ros2_humble/map.py b/exercises/static/exercises/autoparking_lidar/python_template/ros2_humble/map.py new file mode 100644 index 000000000..97d37e173 --- /dev/null +++ b/exercises/static/exercises/autoparking_lidar/python_template/ros2_humble/map.py @@ -0,0 +1,36 @@ +import json +import math +import numpy as np + +class Map: + def __init__(self, lidar_object): + # Define the object used for + # websocket communication + self.payload = {} + + self.lidar_topic = lidar_object + + # Get the JSON data as string + def get_json_data(self): + self.payload["lasers"], self.payload["ranges"] = self.setLaserValues() + + message = json.dumps(self.payload) + return message + + def RTx(self, angle, tx, ty, tz): + RT = np.matrix([[1, 0, 0, tx], [0, math.cos(angle), -math.sin(angle), ty], [0, math.sin(angle), math.cos(angle), tz], [0,0,0,1]]) + return RT + + def RTy(self, angle, tx, ty, tz): + RT = np.matrix([[math.cos(angle), 0, math.sin(angle), tx], [0, 1, 0, ty], [-math.sin(angle), 0, math.cos(angle), tz], [0,0,0,1]]) + return RT + + def RTz(self, angle, tx, ty, tz): + RT = np.matrix([[math.cos(angle), -math.sin(angle), 0, tx], [math.sin(angle), math.cos(angle),0, ty], [0, 0, 1, tz], [0,0,0,1]]) + return RT + + # Interpret the Laser values + def setLaserValues(self): + # Init laser array + self.lidar = self.lidar_topic() + return self.lidar \ No newline at end of file diff --git a/exercises/static/exercises/autoparking_lidar/react-components/AutoparkingRR.js b/exercises/static/exercises/autoparking_lidar/react-components/AutoparkingRR.js new file mode 100644 index 000000000..d5777aa40 --- /dev/null +++ b/exercises/static/exercises/autoparking_lidar/react-components/AutoparkingRR.js @@ -0,0 +1,14 @@ +import * as React from "react"; +import {Fragment} from "react"; + +import "./css/AutoparkingRR.css"; + +const AutoparkingRR = (props) => { + return ( + + {props.children} + + ); +}; + +export default AutoparkingRR; \ No newline at end of file diff --git a/exercises/static/exercises/autoparking_lidar/react-components/Lasers.js b/exercises/static/exercises/autoparking_lidar/react-components/Lasers.js new file mode 100644 index 000000000..19d161bd9 --- /dev/null +++ b/exercises/static/exercises/autoparking_lidar/react-components/Lasers.js @@ -0,0 +1,63 @@ +import React from "react" +import "./css/GUICanvas.css"; +import Car from "../resources/images/car-top-view.svg"; + +const Lasers = (props) => { + const meter = 73; // 1m = 73px + + const [laser, setLaser] = React.useState([]) + const [maxRange, setMaxRange] = React.useState([]) + + React.useEffect(() => { + const callback = (message) => { + if(message.data.update.map){ + const map_data = JSON.parse(message.data.update.map); + console.log(map_data) + setLaser (map_data.lasers[0]) + setMaxRange (map_data.ranges[0]) + console.log(map_data.ranges) + } + // Send the ACK of the msg + window.RoboticsExerciseComponents.commsManager.send("gui", "ack"); + }; + RoboticsExerciseComponents.commsManager.subscribe( + [RoboticsExerciseComponents.commsManager.events.UPDATE], + callback + ); + + return () => { + console.log("TestShowScreen unsubscribing from ['state-changed'] events"); + RoboticsExerciseComponents.commsManager.unsubscribe( + [RoboticsExerciseComponents.commsManager.events.UPDATE], + callback + ); + }; + }, []); + + return ( +
+ + {laser.map(element => { + var ang = -element[1] + var length = (element[0] / 75) * meter; + return ( +
+ )}) + } +
+)}; + +export default Lasers; \ No newline at end of file diff --git a/exercises/static/exercises/autoparking_lidar/react-components/css/AutoparkingRR.css b/exercises/static/exercises/autoparking_lidar/react-components/css/AutoparkingRR.css new file mode 100644 index 000000000..3bdee7925 --- /dev/null +++ b/exercises/static/exercises/autoparking_lidar/react-components/css/AutoparkingRR.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/static/exercises/autoparking_lidar/react-components/css/GUICanvas.css b/exercises/static/exercises/autoparking_lidar/react-components/css/GUICanvas.css new file mode 100644 index 000000000..b8f9412c6 --- /dev/null +++ b/exercises/static/exercises/autoparking_lidar/react-components/css/GUICanvas.css @@ -0,0 +1,24 @@ +#car { + position: absolute; + width: 91px; + height: 100px; + top: calc(50% - 68px); + left: calc(50% - 45.5px); + z-index: 2 +} + +/* .laser-beam { + position: absolute; + background: repeating-linear-gradient( + to right, + rgb(112, 138, 255), + rgb(112, 138, 255) 73px, + rgb(100, 198, 255) 73px, + rgb(100, 198, 255) 146px + ); + background-size: 100% 1px; + bottom: 50%; + left: 50%; + transform-origin: 0% 0%; + z-index: 3; +} */ diff --git a/exercises/static/exercises/autoparking_lidar/resources/images/car-top-view.svg b/exercises/static/exercises/autoparking_lidar/resources/images/car-top-view.svg new file mode 100644 index 000000000..db10abd1f --- /dev/null +++ b/exercises/static/exercises/autoparking_lidar/resources/images/car-top-view.svg @@ -0,0 +1,65 @@ + + + + + + diff --git a/exercises/templates/exercises/3d_reconstruction/exercise.html b/exercises/templates/exercises/3d_reconstruction/exercise.html index 0a6e615f2..24ce4b27d 100644 --- a/exercises/templates/exercises/3d_reconstruction/exercise.html +++ b/exercises/templates/exercises/3d_reconstruction/exercise.html @@ -3,20 +3,20 @@ {% load static %} {% block exercise_header %} - - - - - - - + + + + + + + {% endblock %} {% block react-content %} {% if deployment %} - {% react_component exercise/3d_reconstruction_newmanager/Reconstruction3DRR %} + {% react_component exercise/3d_reconstruction/Reconstruction3DRR %} {% react_component components/containers/MaterialBox id="exercise-container" %} {% react_component components/common/MainAppBar exerciseName="3D Recontruction" url="https://jderobot.github.io/RoboticsAcademy/exercises/ComputerVision/3d_reconstruction"%} {% react_component RA_links/WorldSelectorRA %} {% end_react_component %} @@ -30,7 +30,7 @@ {% react_component components/visualizers/VncConsoleViewer%}{% end_react_component %} {% end_react_component%} {% react_component components/containers/FlexContainer%} - {% react_component exercise/3d_reconstruction_newmanager/SpecificReconstruction3D%}{% end_react_component %} + {% react_component exercise/3d_reconstruction/SpecificReconstruction3D%}{% end_react_component %} {% react_component components/visualizers/GazeboViewer%}{% end_react_component %} {% end_react_component %} {% end_react_component %} @@ -41,7 +41,7 @@ {% end_react_component %} {% end_react_component %} {% else %} - {% react_component exercise/3d_reconstruction_newmanager/Reconstruction3DRR %} + {% react_component exercise/3d_reconstruction/Reconstruction3DRR %} {% react_component components/wrappers/MaterialBox id="exercise-container" %} {% react_component components/layout_components/MainAppBar exerciseName="3D Recontruction" url="https://jderobot.github.io/RoboticsAcademy/exercises/ComputerVision/3d_reconstruction"%} {% react_component components/visualizers/WorldSelector %} {% end_react_component %} @@ -55,7 +55,7 @@ {% react_component components/visualizers/ConsoleViewer%}{% end_react_component %} {% end_react_component%} {% react_component components/wrappers/FlexContainer%} - {% react_component exercise/3d_reconstruction_newmanager/SpecificReconstruction3D%}{% end_react_component %} + {% react_component exercise/3d_reconstruction/SpecificReconstruction3D%}{% end_react_component %} {% react_component components/visualizers/GazeboViewer%}{% end_react_component %} {% end_react_component %} {% end_react_component %} diff --git a/exercises/templates/exercises/amazon_warehouse/exercise.html b/exercises/templates/exercises/amazon_warehouse/exercise.html index 1deee0e79..aa31861e8 100644 --- a/exercises/templates/exercises/amazon_warehouse/exercise.html +++ b/exercises/templates/exercises/amazon_warehouse/exercise.html @@ -6,7 +6,7 @@ {% block react-content %} {% if deployment %} - {% react_component exercise/amazon_warehouse_newmanager/AmazonWarehouseRR %} + {% react_component exercise/amazon_warehouse/AmazonWarehouseRR %} {% react_component components/containers/MaterialBox id="exercise-container" %} {% react_component components/common/MainAppBar exerciseName="Amazon Warehouse" url="https://jderobot.github.io/RoboticsAcademy/exercises/MobileRobots/amazon_warehouse/"%} {% react_component RA_links/WorldSelectorRA %} {% end_react_component %} @@ -20,7 +20,7 @@ {% react_component components/visualizers/VncConsoleViewer%}{% end_react_component %} {% end_react_component%} {% react_component components/containers/FlexContainer%} - {% react_component exercise/amazon_warehouse_newmanager/SpecificAmazonWarehouse %}{% end_react_component %} + {% react_component exercise/amazon_warehouse/SpecificAmazonWarehouse %}{% end_react_component %} {% react_component components/visualizers/GazeboViewer%}{% end_react_component %} {% end_react_component %} {% end_react_component %} @@ -31,7 +31,7 @@ {% end_react_component %} {% end_react_component %} {% else %} - {% react_component exercise/amazon_warehouse_newmanager/AmazonWarehouseRR %} + {% react_component exercise/amazon_warehouse/AmazonWarehouseRR %} {% react_component components/wrappers/MaterialBox id="exercise-container" %} {% react_component components/layout_components/MainAppBar exerciseName="Amazon Warehouse" url="https://jderobot.github.io/RoboticsAcademy/exercises/MobileRobots/amazon_warehouse/"%} {% react_component components/visualizers/WorldSelector %} {% end_react_component %} @@ -45,7 +45,7 @@ {% react_component components/visualizers/ConsoleViewer%}{% end_react_component %} {% end_react_component%} {% react_component components/wrappers/FlexContainer%} - {% react_component exercise/amazon_warehouse_newmanager/SpecificAmazonWarehouse %}{% end_react_component %} + {% react_component exercise/amazon_warehouse/SpecificAmazonWarehouse %}{% end_react_component %} {% react_component components/visualizers/GazeboViewer%}{% end_react_component %} {% end_react_component %} {% end_react_component %} diff --git a/exercises/templates/exercises/autoparking/exercise.html b/exercises/templates/exercises/autoparking/exercise.html index dab05058d..d269b3b23 100644 --- a/exercises/templates/exercises/autoparking/exercise.html +++ b/exercises/templates/exercises/autoparking/exercise.html @@ -6,7 +6,7 @@ {% block react-content %} {% if deployment %} - {% react_component exercise/autoparking_newmanager/AutoparkingRR %} + {% react_component exercise/autoparking/AutoparkingRR %} {% react_component components/containers/MaterialBox id="exercise-container" %} {% react_component components/common/MainAppBar exerciseName="Autoparking" url="https://jderobot.github.io/RoboticsAcademy/exercises/AutonomousCars/autoparking/"%} {% react_component RA_links/WorldSelectorRA %} {% end_react_component %} @@ -20,7 +20,7 @@ {% react_component components/visualizers/VncConsoleViewer%}{% end_react_component %} {% end_react_component%} {% react_component components/containers/FlexContainer%} - {% react_component exercise/autoparking_newmanager/Lasers%}{% end_react_component %} + {% react_component exercise/autoparking/Lasers%}{% end_react_component %} {% react_component components/visualizers/GazeboViewer%}{% end_react_component %} {% end_react_component %} {% end_react_component %} @@ -31,7 +31,7 @@ {% end_react_component %} {% end_react_component %} {% else %} - {% react_component exercise/autoparking_newmanager/AutoparkingRR %} + {% react_component exercise/autoparking/AutoparkingRR %} {% react_component components/wrappers/MaterialBox id="exercise-container" %} {% react_component components/layout_components/MainAppBar exerciseName="Autoparking" url="https://jderobot.github.io/RoboticsAcademy/exercises/AutonomousCars/autoparking/"%} {% react_component components/visualizers/WorldSelector %} {% end_react_component %} @@ -45,7 +45,7 @@ {% react_component components/visualizers/ConsoleViewer%}{% end_react_component %} {% end_react_component%} {% react_component components/wrappers/FlexContainer%} - {% react_component exercise/autoparking_newmanager/Lasers%}{% end_react_component %} + {% react_component exercise/autoparking/Lasers%}{% end_react_component %} {% react_component components/visualizers/GazeboViewer%}{% end_react_component %} {% end_react_component %} {% end_react_component %} diff --git a/exercises/templates/exercises/autoparking_lidar/exercise.html b/exercises/templates/exercises/autoparking_lidar/exercise.html new file mode 100644 index 000000000..488e9d4da --- /dev/null +++ b/exercises/templates/exercises/autoparking_lidar/exercise.html @@ -0,0 +1,59 @@ +{% extends "react_frontend/exercise_base.html" %} +{% load react_component %} + +{% block exercise_header %} +{% endblock %} + +{% block react-content %} + {% if deployment %} + {% react_component exercise/autoparking_lidar/AutoparkingRR %} + {% react_component components/containers/MaterialBox id="exercise-container" %} + {% react_component components/common/MainAppBar exerciseName="Autoparking Lidar" url="https://jderobot.github.io/RoboticsAcademy/exercises/AutonomousCars/autoparking/"%} + {% react_component RA_links/WorldSelectorRA %} {% end_react_component %} + {% end_react_component %} + {% react_component components/containers/MaterialBox id="content" %} + {% react_component components/containers/MaterialBox id="content-exercise" %} + {% react_component components/containers/ExerciseControl %}{% end_react_component %} + {% react_component components/containers/FlexContainer row %} + {% react_component components/containers/FlexContainer console %} + {% react_component components/editors/EditorRobot %}{% end_react_component %} + {% react_component components/visualizers/VncConsoleViewer%}{% end_react_component %} + {% end_react_component%} + {% react_component components/containers/FlexContainer%} + {% react_component exercise/autoparking_lidar/Lasers%}{% end_react_component %} + {% react_component components/visualizers/GazeboViewer%}{% end_react_component %} + {% end_react_component %} + {% end_react_component %} + {% 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 %} + {% else %} + {% react_component exercise/autoparking_lidar/AutoparkingRR %} + {% react_component components/wrappers/MaterialBox id="exercise-container" %} + {% react_component components/layout_components/MainAppBar exerciseName="Autoparking Lidar" url="https://jderobot.github.io/RoboticsAcademy/exercises/AutonomousCars/autoparking/"%} + {% react_component components/visualizers/WorldSelector %} {% 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 console %} + {% react_component components/editors/EditorRobot %}{% end_react_component %} + {% react_component components/visualizers/ConsoleViewer%}{% end_react_component %} + {% end_react_component%} + {% react_component components/wrappers/FlexContainer%} + {% react_component exercise/autoparking_lidar/Lasers%}{% end_react_component %} + {% react_component components/visualizers/GazeboViewer%}{% end_react_component %} + {% end_react_component %} + {% end_react_component %} + {% 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 %} + {% endif %} +{% endblock %} \ No newline at end of file diff --git a/exercises/templates/exercises/follow_line/exercise.html b/exercises/templates/exercises/follow_line/exercise.html index 8100f67c7..1b277dc39 100644 --- a/exercises/templates/exercises/follow_line/exercise.html +++ b/exercises/templates/exercises/follow_line/exercise.html @@ -6,7 +6,7 @@ {% block react-content %} {% if deployment %} - {% react_component exercise/follow_line_newmanager/FollowLineRR %} + {% react_component exercise/follow_line/FollowLineRR %} {% react_component components/containers/MaterialBox id="exercise-container" %} {% react_component components/common/MainAppBar exerciseName="Follow Line" url="https://jderobot.github.io/RoboticsAcademy/exercises/AutonomousCars/follow_line/"%} {% react_component RA_links/WorldSelectorRA %} {% end_react_component %} @@ -31,7 +31,7 @@ {% end_react_component %} {% end_react_component %} {% else %} - {% react_component exercise/follow_line_newmanager/FollowLineRR %} + {% react_component exercise/follow_line/FollowLineRR %} {% react_component components/wrappers/MaterialBox id="exercise-container" %} {% react_component components/layout_components/MainAppBar exerciseName="Follow Line" url="https://jderobot.github.io/RoboticsAcademy/exercises/AutonomousCars/follow_line/"%} {% react_component components/visualizers/WorldSelector %} {% end_react_component %} @@ -45,7 +45,7 @@ {% react_component components/visualizers/ConsoleViewer%}{% end_react_component %} {% end_react_component%} {% react_component components/wrappers/FlexContainer%} - {% react_component exercise/follow_line_newmanager/SpecificFollowLine %}{% end_react_component %} + {% react_component exercise/follow_line/SpecificFollowLine %}{% end_react_component %} {% react_component components/visualizers/GazeboViewer%}{% end_react_component %} {% end_react_component %} {% end_react_component %} diff --git a/exercises/templates/exercises/follow_person/exercise.html b/exercises/templates/exercises/follow_person/exercise.html index 4d50c30a9..f29d7a65f 100644 --- a/exercises/templates/exercises/follow_person/exercise.html +++ b/exercises/templates/exercises/follow_person/exercise.html @@ -6,7 +6,7 @@ {% block react-content %} {% if deployment %} - {% react_component exercise/follow_person_newmanager/FollowPersonRR %} + {% react_component exercise/follow_person/FollowPersonRR %} {% react_component components/containers/MaterialBox id="exercise-container" %} {% react_component components/common/MainAppBar exerciseName="Follow Person" url="https://jderobot.github.io/RoboticsAcademy/exercises/MobileRobots/follow_person"%} {% react_component RA_links/WorldSelectorRA %} {% end_react_component %} @@ -20,7 +20,7 @@ {% react_component components/visualizers/VncConsoleViewer%}{% end_react_component %} {% end_react_component%} {% react_component components/containers/FlexContainer%} - {% react_component exercise/follow_person_newmanager/ImgCanvas %}{% end_react_component %} + {% react_component exercise/follow_person/ImgCanvas %}{% end_react_component %} {% react_component components/visualizers/GazeboViewer%}{% end_react_component %} {% end_react_component %} {% end_react_component %} @@ -31,7 +31,7 @@ {% end_react_component %} {% end_react_component %} {% else %} - {% react_component exercise/follow_person_newmanager/FollowPersonRR %} + {% react_component exercise/follow_person/FollowPersonRR %} {% react_component components/wrappers/MaterialBox id="exercise-container" %} {% react_component components/layout_components/MainAppBar exerciseName="Follow Person" url="https://jderobot.github.io/RoboticsAcademy/exercises/MobileRobots/follow_person"%} {% react_component components/visualizers/WorldSelector %} {% end_react_component %} @@ -45,7 +45,7 @@ {% react_component components/visualizers/ConsoleViewer%}{% end_react_component %} {% end_react_component%} {% react_component components/wrappers/FlexContainer%} - {% react_component exercise/follow_person_newmanager/ImgCanvas %}{% end_react_component %} + {% react_component exercise/follow_person/ImgCanvas %}{% end_react_component %} {% react_component components/visualizers/GazeboViewer%}{% end_react_component %} {% end_react_component %} {% end_react_component %} diff --git a/exercises/templates/exercises/global_navigation/exercise.html b/exercises/templates/exercises/global_navigation/exercise.html index fba07e68f..66ed011a0 100644 --- a/exercises/templates/exercises/global_navigation/exercise.html +++ b/exercises/templates/exercises/global_navigation/exercise.html @@ -6,7 +6,7 @@ {% block react-content %} {% if deployment %} - {% react_component exercise/global_navigation_newmanager/globalNavigationRR %} + {% react_component exercise/global_navigation/globalNavigationRR %} {% react_component components/containers/MaterialBox id="exercise-container" %} {% react_component components/common/MainAppBar exerciseName="Global Navigation" url="https://jderobot.github.io/RoboticsAcademy/exercises/AutonomousCars/global_navigation/"%} {% react_component RA_links/WorldSelectorRA %} {% end_react_component %} @@ -20,7 +20,7 @@ {% react_component components/visualizers/VncConsoleViewer%}{% end_react_component %} {% end_react_component%} {% react_component components/containers/FlexContainer%} - {% react_component exercise/global_navigation_newmanager/GlobalNavigationSpecific %}{% end_react_component %} + {% react_component exercise/global_navigation/GlobalNavigationSpecific %}{% end_react_component %} {% react_component components/visualizers/GazeboViewer%}{% end_react_component %} {% end_react_component %} {% end_react_component %} @@ -31,7 +31,7 @@ {% end_react_component %} {% end_react_component %} {% else %} - {% react_component exercise/global_navigation_newmanager/globalNavigationRR %} + {% react_component exercise/global_navigation/globalNavigationRR %} {% react_component components/wrappers/MaterialBox id="exercise-container" %} {% react_component components/layout_components/MainAppBar exerciseName="Global Navigation" url="https://jderobot.github.io/RoboticsAcademy/exercises/AutonomousCars/global_navigation/"%} {% react_component components/visualizers/WorldSelector %} {% end_react_component %} @@ -45,7 +45,7 @@ {% react_component components/visualizers/ConsoleViewer%}{% end_react_component %} {% end_react_component%} {% react_component components/wrappers/FlexContainer%} - {% react_component exercise/global_navigation_newmanager/GlobalNavigationSpecific %}{% end_react_component %} + {% react_component exercise/global_navigation/GlobalNavigationSpecific %}{% end_react_component %} {% react_component components/visualizers/GazeboViewer%}{% end_react_component %} {% end_react_component %} {% end_react_component %} diff --git a/exercises/templates/exercises/obstacle_avoidance/exercise.html b/exercises/templates/exercises/obstacle_avoidance/exercise.html index 0699487e7..7d53834fc 100644 --- a/exercises/templates/exercises/obstacle_avoidance/exercise.html +++ b/exercises/templates/exercises/obstacle_avoidance/exercise.html @@ -6,7 +6,7 @@ {% block react-content %} {% if deployment %} - {% react_component exercise/obstacle_avoidance_newmanager/ObstacleAvoidanceRR %} + {% react_component exercise/obstacle_avoidance/ObstacleAvoidanceRR %} {% react_component components/containers/MaterialBox id="exercise-container" %} {% react_component components/common/MainAppBar exerciseName="Obstacle Avoidance" url="https://jderobot.github.io/RoboticsAcademy/exercises/AutonomousCars/obstacle_avoidance"%} {% react_component RA_links/WorldSelectorRA %} {% end_react_component %} @@ -20,7 +20,7 @@ {% react_component components/visualizers/VncConsoleViewer%}{% end_react_component %} {% end_react_component%} {% react_component components/containers/FlexContainer%} - {% react_component uniboticsExtra/assets/exercises/obstacle_avoidance_newmanager/SpecificObstacleAvoidance %}{% end_react_component %} + {% react_component uniboticsExtra/assets/exercises/obstacle_avoidance/SpecificObstacleAvoidance %}{% end_react_component %} {% react_component components/visualizers/GazeboViewer%}{% end_react_component %} {% end_react_component %} {% end_react_component %} @@ -31,7 +31,7 @@ {% end_react_component %} {% end_react_component %} {% else %} - {% react_component exercise/obstacle_avoidance_newmanager/ObstacleAvoidanceRR %} + {% react_component exercise/obstacle_avoidance/ObstacleAvoidanceRR %} {% react_component components/wrappers/MaterialBox id="exercise-container" %} {% react_component components/layout_components/MainAppBar exerciseName="Obstacle Avoidance" url="https://jderobot.github.io/RoboticsAcademy/exercises/AutonomousCars/obstacle_avoidance"%} {% react_component components/visualizers/WorldSelector %} {% end_react_component %} @@ -45,7 +45,7 @@ {% react_component components/visualizers/ConsoleViewer%}{% end_react_component %} {% end_react_component%} {% react_component components/wrappers/FlexContainer%} - {% react_component exercise/obstacle_avoidance_newmanager/SpecificObstacleAvoidance %}{% end_react_component %} + {% react_component exercise/obstacle_avoidance/SpecificObstacleAvoidance %}{% end_react_component %} {% react_component components/visualizers/GazeboViewer%}{% end_react_component %} {% end_react_component %} {% end_react_component %} diff --git a/exercises/templates/exercises/rescue_people/exercise.html b/exercises/templates/exercises/rescue_people/exercise.html index ecc899677..cda7ee72f 100644 --- a/exercises/templates/exercises/rescue_people/exercise.html +++ b/exercises/templates/exercises/rescue_people/exercise.html @@ -6,7 +6,7 @@ {% block react-content %} {% if deployment %} - {% react_component exercise/rescue_people_newmanager/rescuePeopleRR %} + {% react_component exercise/rescue_people/rescuePeopleRR %} {% react_component components/containers/MaterialBox id="exercise-container" %} {% react_component components/common/MainAppBar exerciseName="Rescue People" url="https://jderobot.github.io/RoboticsAcademy/exercises/Drones/rescue_people"%} {% react_component RA_links/WorldSelectorRA %} {% end_react_component %} @@ -20,7 +20,7 @@ {% react_component components/visualizers/VncConsoleViewer%}{% end_react_component %} {% end_react_component%} {% react_component components/containers/FlexContainer%} - {% react_component exercise/rescue_people_newmanager/SpecificRescuePeople %} {% end_react_component %} + {% react_component exercise/rescue_people/SpecificRescuePeople %} {% end_react_component %} {% react_component components/visualizers/GazeboViewer%}{% end_react_component %} {% end_react_component %} {% end_react_component %} @@ -31,7 +31,7 @@ {% end_react_component %} {% end_react_component %} {% else %} - {% react_component exercise/rescue_people_newmanager/rescuePeopleRR %} + {% react_component exercise/rescue_people/rescuePeopleRR %} {% react_component components/wrappers/MaterialBox id="exercise-container" %} {% react_component components/layout_components/MainAppBar exerciseName="Rescue People" url="https://jderobot.github.io/RoboticsAcademy/exercises/Drones/rescue_people"%} {% react_component components/visualizers/WorldSelector %} {% end_react_component %} @@ -45,7 +45,7 @@ {% react_component components/visualizers/ConsoleViewer%}{% end_react_component %} {% end_react_component%} {% react_component components/wrappers/FlexContainer%} - {% react_component exercise/rescue_people_newmanager/SpecificRescuePeople %} {% end_react_component %} + {% react_component exercise/rescue_people/SpecificRescuePeople %} {% end_react_component %} {% react_component components/visualizers/GazeboViewer%}{% end_react_component %} {% end_react_component %} {% end_react_component %} diff --git a/exercises/templates/exercises/vacuum_cleaner/exercise.html b/exercises/templates/exercises/vacuum_cleaner/exercise.html index c336474e2..ab3ec7f92 100644 --- a/exercises/templates/exercises/vacuum_cleaner/exercise.html +++ b/exercises/templates/exercises/vacuum_cleaner/exercise.html @@ -6,7 +6,7 @@ {% block react-content %} {% if deployment %} - {% react_component exercise/vacuum_cleaner_newmanager/BasicVacuumCleaner %} + {% react_component exercise/vacuum_cleaner/BasicVacuumCleaner %} {% react_component components/containers/MaterialBox id="exercise-container" %} {% react_component components/common/MainAppBar exerciseName="Basic Vacuum Cleaner" url="https://jderobot.github.io/RoboticsAcademy/exercises/MobileRobots/vacuum_cleaner"%} {% react_component RA_links/WorldSelectorRA %} {% end_react_component %} @@ -14,14 +14,14 @@ {% react_component components/containers/MaterialBox id="content" %} {% react_component components/containers/MaterialBox id="content-exercise" %} {% react_component components/containers/ExerciseControl efficacy %}{% end_react_component %} - {% react_component uniboticsExtra/assets/exercises/vacuum_cleaner_newmanager/GridBasicVacuumCleaner %}{% end_react_component %} + {% react_component uniboticsExtra/assets/exercises/vacuum_cleaner/GridBasicVacuumCleaner %}{% end_react_component %} {% react_component components/containers/FlexContainer row %} {% react_component components/containers/FlexContainer console %} {% react_component components/editors/EditorRobot %}{% end_react_component %} {% react_component components/visualizers/VncConsoleViewer%}{% end_react_component %} {% end_react_component%} {% react_component components/containers/FlexContainer%} - {% react_component uniboticsExtra/assets/exercises/vacuum_cleaner_newmanager/SpecificVacuumCleaner %}{% end_react_component %} + {% react_component uniboticsExtra/assets/exercises/vacuum_cleaner/SpecificVacuumCleaner %}{% end_react_component %} {% react_component components/visualizers/GazeboViewer%}{% end_react_component %} {% end_react_component %} {% end_react_component %} @@ -32,7 +32,7 @@ {% end_react_component %} {% end_react_component %} {% else %} - {% react_component exercise/vacuum_cleaner_newmanager/BasicVacuumCleaner %} + {% react_component exercise/vacuum_cleaner/BasicVacuumCleaner %} {% react_component components/wrappers/MaterialBox id="exercise-container" %} {% react_component components/layout_components/MainAppBar exerciseName="Basic Vacuum Cleaner" url="https://jderobot.github.io/RoboticsAcademy/exercises/MobileRobots/vacuum_cleaner"%} {% react_component components/visualizers/WorldSelector %} {% end_react_component %} @@ -46,7 +46,7 @@ {% react_component components/visualizers/ConsoleViewer%}{% end_react_component %} {% end_react_component%} {% react_component components/wrappers/FlexContainer%} - {% react_component exercise/vacuum_cleaner_newmanager/SpecificVacuumCleaner %}{% end_react_component %} + {% react_component exercise/vacuum_cleaner/SpecificVacuumCleaner %}{% end_react_component %} {% react_component components/visualizers/GazeboViewer%}{% end_react_component %} {% end_react_component %} {% end_react_component %} diff --git a/exercises/templates/exercises/vacuum_cleaner_loc/exercise.html b/exercises/templates/exercises/vacuum_cleaner_loc/exercise.html index b339ea1aa..abe1f3596 100644 --- a/exercises/templates/exercises/vacuum_cleaner_loc/exercise.html +++ b/exercises/templates/exercises/vacuum_cleaner_loc/exercise.html @@ -6,7 +6,7 @@ {% block react-content %} {% if deployment %} - {% react_component exercise/vacuum_cleaner_loc_newmanager/LocVacuumCleaner %} + {% react_component exercise/vacuum_cleaner_loc/LocVacuumCleaner %} {% react_component components/containers/MaterialBox id="exercise-container" %} {% react_component components/common/MainAppBar exerciseName="Localized Vacuum Cleaner" url="https://jderobot.github.io/RoboticsAcademy/exercises/MobileRobots/vacuum_cleaner_loc"%} {% react_component RA_links/WorldSelectorRA %} {% end_react_component %} @@ -14,14 +14,14 @@ {% react_component components/containers/MaterialBox id="content" %} {% react_component components/containers/MaterialBox id="content-exercise" %} {% react_component components/containers/ExerciseControl efficacy %}{% end_react_component %} - {% react_component uniboticsExtra/assets/exercises/vacuum_cleaner_loc_newmanager/GridLocVacuumCleaner %}{% end_react_component %} + {% react_component uniboticsExtra/assets/exercises/vacuum_cleaner_loc/GridLocVacuumCleaner %}{% end_react_component %} {% react_component components/containers/FlexContainer row %} {% react_component components/containers/FlexContainer console %} {% react_component components/editors/EditorRobot %}{% end_react_component %} {% react_component components/visualizers/VncConsoleViewer%}{% end_react_component %} {% end_react_component%} {% react_component components/containers/FlexContainer%} - {% react_component uniboticsExtra/assets/exercises/vacuum_cleaner_loc_newmanager/SpecificLocVacuumCleaner %}{% end_react_component %} + {% react_component uniboticsExtra/assets/exercises/vacuum_cleaner_loc/SpecificLocVacuumCleaner %}{% end_react_component %} {% react_component components/visualizers/GazeboViewer%}{% end_react_component %} {% end_react_component %} {% end_react_component %} @@ -32,7 +32,7 @@ {% end_react_component %} {% end_react_component %} {% else %} - {% react_component exercise/vacuum_cleaner_loc_newmanager/LocVacuumCleaner %} + {% react_component exercise/vacuum_cleaner_loc/LocVacuumCleaner %} {% react_component components/wrappers/MaterialBox id="exercise-container" %} {% react_component components/layout_components/MainAppBar exerciseName="Localized Vacuum Cleaner" url="https://jderobot.github.io/RoboticsAcademy/exercises/MobileRobots/vacuum_cleaner_loc"%} {% react_component components/visualizers/WorldSelector %} {% end_react_component %} @@ -46,7 +46,7 @@ {% react_component components/visualizers/ConsoleViewer%}{% end_react_component %} {% end_react_component%} {% react_component components/wrappers/FlexContainer%} - {% react_component exercise/vacuum_cleaner_loc_newmanager/SpecificLocVacuumCleaner %}{% end_react_component %} + {% react_component exercise/vacuum_cleaner_loc/SpecificLocVacuumCleaner %}{% end_react_component %} {% react_component components/visualizers/GazeboViewer%}{% end_react_component %} {% end_react_component %} {% end_react_component %}