diff --git a/src/assurancetourix/assurancetourix/src/assurancetourix.cpp b/src/assurancetourix/assurancetourix/src/assurancetourix.cpp index 51cda057..c4d3d373 100644 --- a/src/assurancetourix/assurancetourix/src/assurancetourix.cpp +++ b/src/assurancetourix/assurancetourix/src/assurancetourix.cpp @@ -72,7 +72,6 @@ Assurancetourix::Assurancetourix() : Node("assurancetourix") { timer_ = this->create_wall_timer(std::chrono::milliseconds(1000 / refresh_frequency), std::bind(&Assurancetourix::simulation_marker_callback, this)); #endif - //timer_ = this->create_wall_timer(0.3s, std::bind(&Assurancetourix::detect, this)); // to remove for PR RCLCPP_INFO(this->get_logger(), "Assurancetourix has been started"); } diff --git a/src/modules/localisation/localisation/localisation_node.py b/src/modules/localisation/localisation/localisation_node.py index b72822c9..90174b23 100644 --- a/src/modules/localisation/localisation/localisation_node.py +++ b/src/modules/localisation/localisation/localisation_node.py @@ -12,6 +12,7 @@ from rcl_interfaces.msg import SetParametersResult from visualization_msgs.msg import MarkerArray from tf2_ros import StaticTransformBroadcaster +from transformix_msgs.srv import TransformixParametersTransformStamped class Localisation(rclpy.node.Node): @@ -28,13 +29,17 @@ def __init__(self): self._tf.header.frame_id = "map" self._tf.child_frame_id = "odom" self.update_transform() + self.get_initial_tf_srv = self.create_service( + TransformixParametersTransformStamped, + "get_odom_map_tf", + self.get_initial_tf_srv_callback, + ) self.subscription_ = self.create_subscription( MarkerArray, "/allies_positions_markers", self.allies_subscription_callback, 10, ) - self.subscription_ # prevent unused variable warning self.tf_publisher_ = self.create_publisher( TransformStamped, "adjust_odometry", 10 ) @@ -114,6 +119,7 @@ def update_transform(self): self._tf.transform.rotation.y = float(qy) self._tf.transform.rotation.z = float(qz) self._tf.transform.rotation.w = float(qw) + self._initial_tf = self._tf self._tf_brodcaster.sendTransform(self._tf) def allies_subscription_callback(self, msg): @@ -136,6 +142,11 @@ def allies_subscription_callback(self, msg): self.tf_publisher_.publish(self._tf) self.last_odom_update = self.get_clock().now().to_msg().sec + def get_initial_tf_srv_callback(self, request, response): + self.get_logger().info(f"incoming request for {self.robot} odom -> map tf") + response.transform_stamped = self._initial_tf + return response + def main(args=None): """Entrypoint.""" diff --git a/src/modules/robot/behavior_trees/navigate_w_replanning_time.xml b/src/modules/robot/behavior_trees/navigate_w_replanning_time.xml index 7ceb1c0f..27a16821 100644 --- a/src/modules/robot/behavior_trees/navigate_w_replanning_time.xml +++ b/src/modules/robot/behavior_trees/navigate_w_replanning_time.xml @@ -5,7 +5,7 @@ - + diff --git a/src/modules/robot/param/robot.in.yml b/src/modules/robot/param/robot.in.yml index e42f76cd..67b784d6 100644 --- a/src/modules/robot/param/robot.in.yml +++ b/src/modules/robot/param/robot.in.yml @@ -56,33 +56,41 @@ cetautomatix: controller_server: ros__parameters: use_sim_time: !Var use_sim_time - controller_frequency: 40.0 + controller_frequency: 20.0 min_x_velocity_threshold: 0.001 - min_y_velocity_threshold: 0.5 + min_y_velocity_threshold: 0.001 min_theta_velocity_threshold: 0.001 progress_checker_plugin: "progress_checker" goal_checker_plugin: "goal_checker" controller_plugins: ["DynamicFollowPath"] progress_checker: plugin: "nav2_controller::SimpleProgressChecker" - required_movement_radius: 0.5 + required_movement_radius: 0.005 movement_time_allowance: 10.0 goal_checker: plugin: "nav2_controller::SimpleGoalChecker" - xy_goal_tolerance: 0.02 - yaw_goal_tolerance: 0.02 + xy_goal_tolerance: 0.01 + yaw_goal_tolerance: 0.01 stateful: True DynamicFollowPath: plugin: "teb_local_planner::TebLocalPlannerROS" # Robot footprint footprint_model.type: polygon + # Goal tolerance + xy_goal_tolerance: 0.01 + yaw_goal_tolerance: 0.01 + # Obstacles - min_obstacle_dist: 0.01 - inflation_dist: 0.1 + min_obstacle_dist: 0.03 + inflation_dist: 0.25 costmap_converter_plugin: costmap_converter::CostmapToPolygonsDBSMCCH costmap_converter_spin_thread: True costmap_converter_rate: 5 + include_costmap_obstacles: true + costmap_obstacles_behind_robot_dist: 3.0 + include_dynamic_obstacles: true + # Homotopy Class Planner enable_homotopy_class_planning: True @@ -103,6 +111,9 @@ controller_server: global_plan_overwrite_orientation: true allow_init_with_backwards_motion: true + # Miscellaneous + map_frame: "map" + controller_server_rclcpp_node: ros__parameters: @@ -112,12 +123,13 @@ controller_server_rclcpp_node: global_costmap: global_costmap: ros__parameters: + lethal_cost_threshold: 253 update_frequency: 5.0 publish_frequency: 5.0 global_frame: map robot_base_frame: base_link use_sim_time: !Var use_sim_time - resolution: 0.02 + resolution: 0.01 plugins: ["static_layer", "gradient_layer", "inflation_layer"] static_layer: #subscribe to map plugin: "nav2_costmap_2d::StaticLayer" @@ -131,24 +143,42 @@ global_costmap: inflation_layer: plugin: "nav2_costmap_2d::InflationLayer" enabled: true - inflation_radius: 0.2 - cost_scaling_factor: 5.0 + inflation_radius: 0.3 + cost_scaling_factor: 10.0 inflate_unknown: false inflate_around_unknown: false always_send_full_costmap: true -local_costmap: #just enough parameters to disable it +local_costmap: local_costmap: ros__parameters: - update_frequency: 0.1 - publish_frequency: 0.1 + lethal_cost_threshold: 253 + trinary_costmap: false + update_frequency: 5.0 + publish_frequency: 5.0 global_frame: map robot_base_frame: base_link use_sim_time: false - rolling_window: true - width: 6 - height: 6 + rolling_window: false resolution: 1.0 + static_map: true + plugins: ["static_layer", "gradient_layer", "inflation_layer"] + static_layer: + plugin: nav2_costmap_2d::StaticLayer + gradient_layer: #draw radians circle around ennemies + plugin: "gradient_costmap_layer_plugin/GradientLayer" + enabled: false + gradient_size: 7 + gradient_factor: 100 + markers_topic: /ennemies_positions_markers + inflation_layer: + plugin: nav2_costmap_2d::InflationLayer + enabled: false + inflation_radius: 0.01 + cost_scaling_factor: 5.0 + inflate_unknown: false + inflate_around_unknown: false + always_send_full_costmap: true map_server: ros__parameters: diff --git a/src/modules/robot/robot/launcher.py b/src/modules/robot/robot/launcher.py index 8aa83290..8cabe0b9 100644 --- a/src/modules/robot/robot/launcher.py +++ b/src/modules/robot/robot/launcher.py @@ -126,6 +126,12 @@ def generate_robot_launch_description(robot_namespace: str, simulation=False): parameters=[params.name], remappings=remappings, ), + Node( + package="teb_obstacles", + executable="teb_obstacles", + output="screen", + parameters=[], + ), IncludeLaunchDescription( PythonLaunchDescriptionSource( [nav2_launch_file_dir, "/navigation_launch.py"] diff --git a/src/navigation/teb_obstacles/package.xml b/src/navigation/teb_obstacles/package.xml new file mode 100644 index 00000000..f1bf23e6 --- /dev/null +++ b/src/navigation/teb_obstacles/package.xml @@ -0,0 +1,15 @@ + + + + teb_obstacles + 0.8.3 + teb_obstacles node compute and send dynamic teb_obstacles + Philéas LAMBERT + ECAM Makers :: CDFR 2021 + + rclpy + + + ament_python + + diff --git a/src/navigation/teb_obstacles/resource/teb_obstacles b/src/navigation/teb_obstacles/resource/teb_obstacles new file mode 100644 index 00000000..e69de29b diff --git a/src/navigation/teb_obstacles/setup.cfg b/src/navigation/teb_obstacles/setup.cfg new file mode 100644 index 00000000..b166fdb2 --- /dev/null +++ b/src/navigation/teb_obstacles/setup.cfg @@ -0,0 +1,4 @@ +[develop] +script-dir=$base/lib/teb_obstacles +[install] +install-scripts=$base/lib/teb_obstacles diff --git a/src/navigation/teb_obstacles/setup.py b/src/navigation/teb_obstacles/setup.py new file mode 100644 index 00000000..eafba6de --- /dev/null +++ b/src/navigation/teb_obstacles/setup.py @@ -0,0 +1,31 @@ +#!/usr/bin/env python3 + + +"""Teb_obstacles package.""" + + +from os import path +from setuptools import setup, find_packages + +package_name = "teb_obstacles" + +setup( + name=package_name, + version="0.8.3", + packages=find_packages(), + data_files=[ + (path.join("share", package_name), ["package.xml"]), + ("share/ament_index/resource_index/packages", ["resource/" + package_name]), + ], + install_requires=["setuptools"], + zip_safe=True, + author="Philéas LAMBERT", + maintainer="Phileas LAMBERT", + maintainer_email="phileas.lambert@gmail.com", + keywords=["ROS2", "teb_obstacles", "CDFR"], + description="teb_obstacles node compute and send dynamic teb_obstacles", + license="ECAM Makers :: CDFR 2021", + entry_points={ + "console_scripts": ["teb_obstacles = teb_obstacles.teb_obstacles:main"], + }, +) diff --git a/src/navigation/teb_obstacles/teb_obstacles/__init__.py b/src/navigation/teb_obstacles/teb_obstacles/__init__.py new file mode 100644 index 00000000..e69de29b diff --git a/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py b/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py new file mode 100644 index 00000000..c617c544 --- /dev/null +++ b/src/navigation/teb_obstacles/teb_obstacles/teb_obstacles.py @@ -0,0 +1,175 @@ +#!/usr/bin/env python3 + + +"""Teb_obstacles localisation node.""" + + +import rclpy +import copy + +from rclpy.node import Node +from costmap_converter_msgs.msg import ObstacleArrayMsg, ObstacleMsg +from visualization_msgs.msg import MarkerArray, Marker +from nav_msgs.msg import Odometry +from geometry_msgs.msg import Point32 +from platform import machine +from transformix_msgs.srv import TransformixParametersTransformStamped + + +class Teb_obstacles(Node): + def __init__(self): + super().__init__("teb_dynamic_obstacles_node") + self.simulation = True if machine() != "aarch64" else False + + self.ally = ( + "obelix" if self.get_namespace().strip("/") == "asterix" else "asterix" + ) + + self.get_ally_odom_transformation() + + self.allies_subscription_ = self.create_subscription( + Odometry, f"/{self.ally}/odom", self.allies_subscription_callback, 10 + ) + self.enemies_subscription_ = self.create_subscription( + MarkerArray, + "/enemies_positions_markers", + self.enemies_subscription_callback, + 10, + ) + + self.obstacles_publisher_ = self.create_publisher( + ObstacleArrayMsg, "obstacles", 10 + ) + + self.enemies_markers_ids = [0, 0] + + self.last_time_ally_callback = self.get_clock().now().to_msg() + + self.initObstaclesArray() + + self.create_timer(0.5, self.send_obstacles) + + self.get_logger().info("teb_dynamic_obstacles node is ready") + + def get_ally_odom_transformation(self): + if self.simulation: + return + + get_tf_client = self.create_client( + TransformixParametersTransformStamped, f"/{self.ally}/get_odom_map_tf" + ) + + if not get_tf_client.wait_for_service(timeout_sec=15.0): + self.get_logger().info( + f"No service /{self.ally}/get_odom_map_tf availible, is there ony one robot?" + ) + return + get_tf_request = TransformixParametersTransformStamped.Request() + future = get_tf_client.call_async(get_tf_request) + rclpy.spin_until_future_complete(self, future) + try: + response = future.result() + except Exception as e: + self.get_logger().info("Service call failed %r" % (e,)) + else: + self.odom_map_tf = response.transform_stamped + + def initObstaclesArray(self): + """ObstacleArray index 0: ally, index 1-2: enemies""" + self.obstacles = ObstacleArrayMsg() + self.obstacles.header.frame_id = "map" + self.obstacles.obstacles.append(ObstacleMsg()) + self.obstacles.obstacles.append(ObstacleMsg()) + self.obstacles.obstacles.append(ObstacleMsg()) + for i in range(3): + self.obstacles.obstacles[i].header.frame_id = "map" + self.obstacles.obstacles[i].polygon.points = [Point32()] + self.obstacles.obstacles[i].polygon.points[0].x = -1.0 + self.obstacles.obstacles[i].polygon.points[0].y = -1.0 + self.obstacles.obstacles[i].radius = 0.15 + self.previous_obstacles = copy.deepcopy(self.obstacles) + + def get_diff_time(self, t1, t2): + """Returns the nb of seconds between the two Time object""" + return t1.sec - t2.sec + (t1.nanosec - t2.nanosec) * 1e-9 + + def set_obstacle(self, index, marker): + """Set the marker as obstacle in ObstacleArrayMsg at the given index, + compute the linear velocities relative to the previous state""" + self.previous_obstacles.obstacles[index] = copy.deepcopy( + self.obstacles.obstacles[index] + ) + self.obstacles.obstacles[index].header = marker.header + self.obstacles.obstacles[index].polygon.points[0].x = marker.pose.position.x + self.obstacles.obstacles[index].polygon.points[0].y = marker.pose.position.y + + dt = float( + self.get_diff_time( + marker.header.stamp, + self.previous_obstacles.obstacles[index].header.stamp, + ) + ) + + if dt != 0.0: + self.obstacles.obstacles[index].velocities.twist.linear.x = ( + marker.pose.position.x + - self.previous_obstacles.obstacles[index].polygon.points[0].x + ) / dt + + self.obstacles.obstacles[index].velocities.twist.linear.y = ( + marker.pose.position.y + - self.previous_obstacles.obstacles[index].polygon.points[0].y + ) / dt + + def allies_subscription_callback(self, msg): + """Determine the pose of base_link in map + set the dynamic obstacle for teb_local_planner""" + if ( + self.get_diff_time( + self.get_clock().now().to_msg(), self.last_time_ally_callback + ) + > 0.3 + ): + pose = msg.pose.pose + x = pose.position.x + self.odom_map_tf.transform.translation.x + y = pose.position.y + self.odom_map_tf.transform.translation.y + tmp_marker = Marker() + tmp_marker.pose.position.x = x + tmp_marker.pose.position.y = y + self.set_obstacle(0, tmp_marker) + self.last_time_ally_callback = self.get_clock().now().to_msg() + + def enemies_subscription_callback(self, msg): + """Identify the enemy marker in assurancetourix marker_array detection + set the dynamic obstacle for teb_local_planner""" + for enemy_marker in msg.markers: + if enemy_marker.id <= 10: # >10 are predicted markers + marker_stored = False + for index in range(2): + if self.enemies_markers_ids[index] == enemy_marker.id: + self.set_obstacle(index + 1, enemy_marker) + marker_stored = True + if not marker_stored: + if self.enemies_markers_ids[0] == 0: + self.enemies_markers_ids[0] = enemy_marker.id + elif self.enemies_markers_ids[1] == 0: + self.enemies_markers_ids[1] = enemy_marker.id + else: + self.get_logger().info( + "obstacleArray index limit, are there 3 enemies, or is it a bad marker detection" + ) + + def send_obstacles(self): + self.obstacles_publisher_.publish(self.obstacles) + + +def main(args=None): + """Entrypoint.""" + rclpy.init(args=args) + teb_obstacles = Teb_obstacles() + try: + rclpy.spin(teb_obstacles) + except KeyboardInterrupt: + pass + teb_obstacles.destroy_node() + rclpy.shutdown() diff --git a/tools/simulation/protos/Asterix.proto b/tools/simulation/protos/Asterix.proto index 914c8332..9edf73b8 100644 --- a/tools/simulation/protos/Asterix.proto +++ b/tools/simulation/protos/Asterix.proto @@ -11,7 +11,7 @@ PROTO Asterix [ field SFString controller "" # Is `Robot.controller`. field MFString controllerArgs [] # Is `Robot.controllerArgs`. field SFString customData "" # Is `Robot.customData`. - field SFBool supervisor FALSE # Is `Robot.supervisor`. + field SFBool supervisor TRUE # Is `Robot.supervisor`. field SFBool synchronization FALSE # Is `Robot.synchronization`. field MFNode arucoTag [ Aruco { } ] # Is `Robot.arucoTag`. ] @@ -141,7 +141,7 @@ PROTO Asterix [ VL53L1X { name "vlx_0x30" translation 0.08 -0.13 -0.14 - rotation 0 0 1 1.5708 + rotation 0 0 1 -1.5708 } VL53L1X { name "vlx_0x31" @@ -156,7 +156,7 @@ PROTO Asterix [ VL53L1X { name "vlx_0x33" translation 0.08 0.13 -0.14 - rotation 0 0 1 -1.5708 + rotation 0 0 1 1.5708 } VL53L1X { name "vlx_0x34" diff --git a/tools/simulation/protos/VL53L1X.proto b/tools/simulation/protos/VL53L1X.proto index 911d9002..86802d70 100644 --- a/tools/simulation/protos/VL53L1X.proto +++ b/tools/simulation/protos/VL53L1X.proto @@ -10,9 +10,9 @@ PROTO VL53L1X [ translation IS translation rotation IS rotation lookupTable [ 0 0 0 , - 0.02 0.01 0.005, - 3000 3000 0.01 , - 3500 0 0 ] + 0.02 20 0.0001, + 3.5 3500 0.0001, + 4.0 0 0 ] type "laser" numberOfRays 1 resolution -1 diff --git a/tools/simulation/worlds/cdr2020.wbt b/tools/simulation/worlds/cdr2020.wbt index 3121721c..26cc2531 100644 --- a/tools/simulation/worlds/cdr2020.wbt +++ b/tools/simulation/worlds/cdr2020.wbt @@ -48,223 +48,223 @@ DEF ASTERIX Asterix { DEF PHARAON Pharaon { translation 2.78 0.07 -0.11 } -RedSignal { +DEF GOB2 RedSignal { translation 0.3 0 0.4 name "GOB2" } -RedSignal { +DEF GOB3 RedSignal { translation 0.45 0 1.08 name "GOB3" } -RedSignal { +DEF GOB5 RedSignal { translation 0.67 0 0.1 name "GOB5" } -RedSignal { +DEF GOB7 RedSignal { translation 1.005 0 1.955 name "GOB7" } -RedSignal { +DEF GOB9 RedSignal { translation 1.1 0 0.8 name "GOB9" } -RedSignal { +DEF GOB11 RedSignal { translation 1.335 0 1.65 name "GOB11" } -RedSignal { +DEF GOB13 RedSignal { translation 1.605 0 1.955 name "GOB13" } -RedSignal { +DEF GOB15 RedSignal { translation 1.73 0 1.2 name "GOB15" } -RedSignal { +DEF GOB17 RedSignal { translation 1.935 0 1.65 name "GOB17" } -RedSignal { +DEF GOB19 RedSignal { translation 2.05 0 0.4 name "GOB19" } -RedSignal { +DEF GOB22 RedSignal { translation 2.55 0 0.51 name "GOB22" } -RedSignal { +DEF GOB23 RedSignal { translation 2.7 0 1.2 name "GOB23" } -RedSignal { +DEF GOB25 RedSignal { translation -0.067 0.132 1.45 rotation 1 0 0 3.1415 name "GOB25" } -RedSignal { +DEF GOB27 RedSignal { translation -0.067 0.132 1.6 rotation 1 0 0 3.1415 name "GOB27" } -RedSignal { +DEF GOB29 RedSignal { translation -0.067 0.132 1.75 rotation 1 0 0 3.1415 name "GOB29" } -RedSignal { +DEF GOB31 RedSignal { translation 3.067 0.132 1.525 rotation 1 0 0 3.1415 name "GOB31" } -RedSignal { +DEF GOB33 RedSignal { translation 3.067 0.132 1.675 rotation 1 0 0 3.1415 name "GOB33" } -RedSignal { +DEF GOB36 RedSignal { translation 0.775 0.132 -0.067 rotation 1 0 0 3.1415 name "GOB36" } -RedSignal { +DEF GOB39 RedSignal { translation 1 0.132 -0.067 rotation 1 0 0 3.1415 name "GOB39" } -RedSignal { +DEF GOB41 RedSignal { translation 2.075 0.132 -0.067 rotation 1 0 0 3.1415 name "GOB41" } -RedSignal { +DEF GOB42 RedSignal { translation 2.15 0.132 -0.067 rotation 1 0 0 3.1415 name "GOB42" } -RedSignal { +DEF GOB44 RedSignal { translation 2.3 0.132 -0.067 rotation 1 0 0 3.1415 name "GOB44" } -GreenSignal { +DEF GOB1 GreenSignal { translation 0.3 0 1.2 name "GOB1" } -GreenSignal { +DEF GOB4 GreenSignal { translation 0.45 0 0.51 name "GOB4" } -GreenSignal { +DEF GOB6 GreenSignal { translation 0.95 0 0.4 name "GOB6" } -GreenSignal { +DEF GOB8 GreenSignal { translation 1.065 0 1.65 name "GOB8" } -GreenSignal { +DEF GOB10 GreenSignal { translation 1.27 0 1.2 name "GOB10" } -GreenSignal { +DEF GOB12 GreenSignal { translation 1.395 0 1.955 name "GOB12" } -GreenSignal { +DEF GOB14 GreenSignal { translation 1.665 0 1.65 name "GOB14" } -GreenSignal { +DEF GOB16 GreenSignal { translation 1.9 0 0.8 name "GOB16" } -GreenSignal { +DEF GOB18 GreenSignal { translation 1.995 0 1.955 name "GOB18" } -GreenSignal { +DEF GOB20 GreenSignal { translation 2.33 0 0.1 name "GOB20" } -GreenSignal { +DEF GOB21 GreenSignal { translation 2.55 0 1.08 name "GOB21" } -GreenSignal { +DEF GOB24 GreenSignal { translation 2.7 0 0.4 name "GOB24" } -GreenSignal { +DEF GOB26 GreenSignal { translation -0.067 0.132 1.525 rotation 1 0 0 3.1415 name "GOB26" } -GreenSignal { +DEF GOB28 GreenSignal { translation -0.067 0.132 1.675 rotation 1 0 0 3.1415 name "GOB28" } -GreenSignal { +DEF GOB30 GreenSignal { translation 3.067 0.132 1.45 rotation 1 0 0 3.1415 name "GOB30" } -GreenSignal { +DEF GOB32 GreenSignal { translation 3.067 0.132 1.6 rotation 1 0 0 3.1415 name "GOB32" } -GreenSignal { +DEF GOB34 GreenSignal { translation 3.067 0.132 1.75 rotation 1 0 0 3.1415 name "GOB34" } -GreenSignal { +DEF GOB35 GreenSignal { translation 0.7 0.132 -0.067 rotation 1 0 0 3.1415 name "GOB35" } -GreenSignal { +DEF GOB37 GreenSignal { translation 0.85 0.132 -0.067 rotation 1 0 0 3.1415 name "GOB37" } -GreenSignal { +DEF GOB38 GreenSignal { translation 0.925 0.132 -0.067 rotation 1 0 0 3.1415 name "GOB38" } -GreenSignal { +DEF GOB40 GreenSignal { translation 2 0.132 -0.067 rotation 1 0 0 3.1415 name "GOB40" } -GreenSignal { +DEF GOB43 GreenSignal { translation 2.225 0.132 -0.067 rotation 1 0 0 3.1415 name "GOB43" } -GreenSignal { +DEF GOB45 GreenSignal { translation 1.73 0 0.35 name "GOB45" } -GreenSignal { +DEF GOB46 GreenSignal { translation 1.6 0 0.14 name "GOB46" } -GreenSignal { +DEF GOB47 GreenSignal { translation 1.22 0 0.33 name "GOB47" } -RedSignal { +DEF GOB48 RedSignal { translation 1.12 0 0.13 name "GOB48" } -RedSignal { +DEF GOB49 RedSignal { translation 1.45 0 0.4 name "GOB49" } -RedSignal { +DEF GOB50 RedSignal { translation 1.91 0 0.16 name "GOB50" }