Skip to content

Commit ab7100e

Browse files
committed
Add support for ROS 2 with CARLA simulator
1 parent 9f5d771 commit ab7100e

17 files changed

+190
-41
lines changed

behavior_metrics/brains/CARLA/brain_carla_segmentation_based_imitation_learning.py

+4-1
Original file line numberDiff line numberDiff line change
@@ -151,14 +151,17 @@ def execute(self):
151151
self.running_light = False
152152

153153
print(f'high-level command: {hlc}')
154-
#print(f'light: {light_status}')
154+
# print(f'light: {light_status}')
155155
frame_data = {
156156
'hlc': hlc,
157157
'measurements': speed,
158158
'rgb': np.copy(rgb_image),
159159
'segmentation': np.copy(seg_image),
160160
'light': np.array([traffic_light_to_int(light_status)])
161161
}
162+
163+
print(frame_data['rgb'].shape)
164+
print(frame_data['segmentation'].shape)
162165

163166
throttle, steer, brake = model_control(self.net,
164167
frame_data,

behavior_metrics/brains/CARLA/brain_carla_slow_and_turn.py

-1
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,6 @@
1212
from utils.constants import DATASETS_DIR, ROOT_PATH
1313

1414

15-
1615
GENERATED_DATASETS_DIR = ROOT_PATH + '/' + DATASETS_DIR
1716

1817

behavior_metrics/brains/CARLA/utils/test_utils.py

+2-1
Original file line numberDiff line numberDiff line change
@@ -117,7 +117,8 @@ def filter_classes(rgb, seg, classes_to_keep = [1, 7, 12, 13, 14, 15, 16, 17, 18
117117

118118
# Use the mask to replace the corresponding pixels in the filtered images
119119
filtered_seg[mask] = seg[mask]
120-
filtered_rgb[mask] = rgb[mask]
120+
filtered_rgb[mask] = rgb[mask]
121+
121122

122123
return filtered_rgb, filtered_seg
123124

behavior_metrics/brains/brains_handler.py

+8-2
Original file line numberDiff line numberDiff line change
@@ -34,27 +34,33 @@ def __init__(self, sensors, actuators, brain_path, controller, model=None, confi
3434
def load_brain(self, path, model=None):
3535

3636
path_split = path.split("/")
37-
robot_type = path_split[1]
37+
framework = path_split[-3]
38+
robot_type = path_split[-2]
3839
module_name = path_split[-1][:-3] # removing .py extension
40+
41+
# import_name = 'brains.' + framework + '.' + robot_type + '.' + module_name
42+
3943
if len(path_split) == 4:
4044
framework = path_split[2]
4145
import_name = 'brains.' + robot_type + '.' + framework + '.' + module_name
4246
else:
4347
import_name = 'brains.' + robot_type + '.' + module_name
48+
print(import_name)
4449

4550
if robot_type == 'CARLA':
4651
module = importlib.import_module(import_name)
4752
Brain = getattr(module, 'Brain')
53+
print('Brain: ', Brain)
4854
if self.model:
4955
self.active_brain = Brain(self.sensors, self.actuators, handler=self, model=self.model,
5056
config=self.config)
5157
else:
5258
self.active_brain = Brain(self.sensors, self.actuators, handler=self, config=self.config)
59+
print('config: ', self.sensors)
5360
else:
5461
if import_name in sys.modules: # for reloading sake
5562
del sys.modules[import_name]
5663
module = importlib.import_module(import_name)
57-
Brain = getattr(module, 'Brain')
5864
if robot_type == 'drone':
5965
self.active_brain = Brain(handler=self, config=self.config)
6066
else:
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,135 @@
1+
#!/usr/bin/env python3
2+
from launch import LaunchDescription
3+
from launch.actions import DeclareLaunchArgument
4+
from launch.substitutions import LaunchConfiguration
5+
from launch_ros.actions import Node
6+
7+
def generate_launch_description():
8+
# Declarar argumentos equivalentes a los <arg> del XML
9+
host_arg = DeclareLaunchArgument(
10+
'host',
11+
default_value='localhost',
12+
description='IP o nombre de host de CARLA'
13+
)
14+
port_arg = DeclareLaunchArgument(
15+
'port',
16+
default_value='2000',
17+
description='Puerto de CARLA'
18+
)
19+
timeout_arg = DeclareLaunchArgument(
20+
'timeout',
21+
default_value='10',
22+
description='Timeout (segundos) de conexión'
23+
)
24+
town_arg = DeclareLaunchArgument(
25+
'town',
26+
default_value='Town01', # o puedes dejarlo vacío si quieres
27+
description='Mapa/town que va a cargar CARLA'
28+
)
29+
spawn_point_arg = DeclareLaunchArgument(
30+
'spawn_point',
31+
default_value='0',
32+
description='Spawn point para ego_vehicle'
33+
)
34+
passive_arg = DeclareLaunchArgument(
35+
'passive',
36+
default_value='',
37+
description='Activar modo pasivo (true/false). Por defecto vacío'
38+
)
39+
synchronous_mode_arg = DeclareLaunchArgument(
40+
'synchronous_mode',
41+
default_value='True',
42+
description='Habilitar modo síncrono en CARLA'
43+
)
44+
synchronous_wait_arg = DeclareLaunchArgument(
45+
'synchronous_mode_wait_for_vehicle_control_command',
46+
default_value='False',
47+
description='Esperar comandos de control de vehículo en modo síncrono'
48+
)
49+
fixed_delta_arg = DeclareLaunchArgument(
50+
'fixed_delta_seconds',
51+
default_value='0.05',
52+
description='Delta de tiempo fijo en modo síncrono'
53+
)
54+
objects_def_file_arg = DeclareLaunchArgument(
55+
'objects_definition_file',
56+
default_value='$(env OBJECT_PATH)/main_car_custom_camera.json',
57+
description='JSON con la definición de objetos (vehículos, sensores, etc.)'
58+
)
59+
ego_vehicle_role_arg = DeclareLaunchArgument(
60+
'ego_vehicle_role_name',
61+
default_value='ego_vehicle',
62+
description='Rol del vehículo ego'
63+
)
64+
65+
# Nodo para el bridge de ROS con CARLA
66+
carla_ros_bridge_node = Node(
67+
package='carla_ros_bridge',
68+
executable='bridge.py',
69+
name='carla_ros_bridge',
70+
output='screen',
71+
parameters=[{
72+
'host': LaunchConfiguration('host'),
73+
'port': LaunchConfiguration('port'),
74+
'timeout': LaunchConfiguration('timeout'),
75+
'passive': LaunchConfiguration('passive'),
76+
'synchronous_mode': LaunchConfiguration('synchronous_mode'),
77+
'synchronous_mode_wait_for_vehicle_control_command': LaunchConfiguration('synchronous_mode_wait_for_vehicle_control_command'),
78+
'fixed_delta_seconds': LaunchConfiguration('fixed_delta_seconds'),
79+
'register_all_sensors': True,
80+
'town': LaunchConfiguration('town'),
81+
'ego_vehicle_role_name': LaunchConfiguration('ego_vehicle_role_name')
82+
}]
83+
)
84+
85+
# Nodo para spawnear los objetos (vehículos, sensores, etc.)
86+
spawn_objects_node = Node(
87+
package='carla_spawn_objects',
88+
executable='carla_spawn_objects.py',
89+
name='carla_spawn_objects',
90+
output='screen',
91+
parameters=[{
92+
'objects_definition_file': LaunchConfiguration('objects_definition_file'),
93+
# Observa cómo el "spawn_point_$(arg ego_vehicle_role_name)" del XML
94+
# se “mapea” ahora a un diccionario en Python. Normalmente, si
95+
# carla_spawn_objects.py procesa un parámetro llamado
96+
# "spawn_point_ego_vehicle", lo indicamos así:
97+
'spawn_point_ego_vehicle': LaunchConfiguration('spawn_point'),
98+
'spawn_sensors_only': False
99+
}]
100+
)
101+
102+
# Nodo para el control manual (carla_manual_control.launch se traduce a un Node)
103+
# Si el package carla_manual_control trae un launch.py, puedes hacer un IncludeLaunchDescription.
104+
# Si es un ejecutable Python, lo llamas con Node. Aquí asumimos que es un script:
105+
manual_control_node = Node(
106+
package='carla_manual_control',
107+
executable='carla_manual_control',
108+
name='carla_manual_control',
109+
output='screen',
110+
# El script seguramente necesitará un argumento 'role_name' (equivalente a la arg del XML).
111+
# Muchos scripts en carla_manual_control usan un param o un arg 'role_name' o 'rolename':
112+
parameters=[{
113+
'role_name': LaunchConfiguration('ego_vehicle_role_name')
114+
}]
115+
)
116+
117+
# Juntamos todo en el LaunchDescription
118+
return LaunchDescription([
119+
# Primero declaramos todos los argumentos
120+
host_arg,
121+
port_arg,
122+
timeout_arg,
123+
town_arg,
124+
spawn_point_arg,
125+
passive_arg,
126+
synchronous_mode_arg,
127+
synchronous_wait_arg,
128+
fixed_delta_arg,
129+
objects_def_file_arg,
130+
ego_vehicle_role_arg,
131+
# Luego añadimos los nodos
132+
carla_ros_bridge_node,
133+
spawn_objects_node,
134+
manual_control_node
135+
])

behavior_metrics/configs/CARLA/CARLA_launch_files/town_02_anticlockwise.launch.py

-2
Original file line numberDiff line numberDiff line change
@@ -4,8 +4,6 @@
44

55
from utils.logger import logger
66

7-
logger.info('Loading town_02_anticlockwise.launch.py') # erase this line
8-
print('Loading town_02_anticlockwise.launch.py') # erase this line
97

108
def generate_launch_description():
119
ld = launch.LaunchDescription([

behavior_metrics/configs/CARLA/default_carla_ros2.yml

+1-1
Original file line numberDiff line numberDiff line change
@@ -47,7 +47,7 @@ Behaviors:
4747
ImageTranform: ''
4848
Type: 'CARLA'
4949
Simulation:
50-
# World: configs/CARLA/CARLA_launch_files/town_02_anticlockwise.launch
50+
# World: configs/CARLA/CARLA_launch_files/town_02_anticlockwise.launch.py
5151
# World: configs/CARLA/CARLA_launch_files/ros2_town02.launch.py
5252
World: configs/CARLA/CARLA_launch_files/town_01_anticlockwise.launch.py
5353
RandomSpawnPoint: False

behavior_metrics/configs/CARLA/default_carla_test_suite.yml

+2-1
Original file line numberDiff line numberDiff line change
@@ -53,7 +53,8 @@ Behaviors:
5353
Timeout: [500] # for each world!
5454
Simulation:
5555
Task: "follow_route"
56-
World: [configs/CARLA/CARLA_launch_files/test_suite_template.launch]
56+
# World: [configs/CARLA/CARLA_launch_files/test_suite_template.launch.py]
57+
World: [configs/CARLA/CARLA_launch_files/town_01_anticlockwise.launch.py]
5758
TestSuite: 'Town02_two_turns'
5859
RandomizeRoutes: False
5960
NumRoutes: 2

behavior_metrics/configs/CARLA/default_carla_torch.yml

+2-1
Original file line numberDiff line numberDiff line change
@@ -47,7 +47,8 @@ Behaviors:
4747
ImageTranform: ''
4848
Type: 'CARLA'
4949
Simulation:
50-
World: configs/CARLA/CARLA_launch_files/town_02_anticlockwise_imitation_learning.launch
50+
# World: configs/CARLA/CARLA_launch_files/town_02_anticlockwise_imitation_learning.launch
51+
World: configs/CARLA/CARLA_launch_files/town_01_anticlockwise.launch.py
5152
RandomSpawnPoint: False
5253
Dataset:
5354
In: '/tmp/my_bag.bag'

behavior_metrics/driver_carla.py

+5-6
Original file line numberDiff line numberDiff line change
@@ -20,8 +20,8 @@
2020
from datetime import datetime
2121
from pilot_carla import PilotCarla
2222

23-
from robot.interfaces.motors import PublisherMotors # erase this line
24-
from robot.actuators import Actuators # erase this line
23+
from robot.interfaces.motors import PublisherMotors
24+
from robot.actuators import Actuators
2525

2626

2727
import matplotlib.pyplot as plt
@@ -352,9 +352,9 @@ def main():
352352
node = init_node(config_data['ros_version']) # Initialize the ROS node shared by all the application
353353

354354
app_configuration = Config(config_data['config'][0])
355-
356-
motors = PublisherMotors(node,'motors', 1, 1, 0, 0) # Create the motors instance, new erase this line
357-
actuators = Actuators(app_configuration.actuators, node) # Create the actuators instance, new erase this line
355+
356+
motors = PublisherMotors(node,'motors', 1, 1, 0, 0) # Create the motors instance
357+
actuators = Actuators(app_configuration.actuators, node) # Create the actuators instance
358358

359359
if not config_data['script']:
360360
if app_configuration.task not in ['follow_lane', 'follow_lane_traffic']:
@@ -373,7 +373,6 @@ def main():
373373
if hasattr(app_configuration, 'experiment_model'):
374374
experiment_model = app_configuration.experiment_model
375375
pilot = PilotCarla(node, app_configuration, controller, app_configuration.brain_path, experiment_model=experiment_model)
376-
logger.info("launch control") # erase this line
377376
else:
378377
pilot = PilotCarla(app_configuration, controller, app_configuration.brain_path)
379378
pilot.daemon = True

behavior_metrics/pilot_carla.py

+1-1
Original file line numberDiff line numberDiff line change
@@ -104,7 +104,7 @@ def __init__(self, node: Node, configuration, controller, brain_path, experiment
104104
self.time_cycle = self.configuration.pilot_time_cycle
105105
self.async_mode = self.configuration.async_mode
106106
self.waypoint_publisher_path = self.configuration.waypoint_publisher_path
107-
107+
108108
def __wait_carla(self):
109109
"""Wait for simulator to be initialized"""
110110

behavior_metrics/robot/sensors.py

+1-1
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,7 @@
1919
try:
2020
from robot.interfaces.birdeyeview import BirdEyeView
2121
except ModuleNotFoundError as ex:
22-
logger.error('CARLA is not supported sensor 1') # erase this line
22+
logger.error('CARLA is not supported sensor')
2323

2424
from robot.interfaces.speedometer import ListenerSpeedometer
2525

behavior_metrics/test_suite_manager_carla.py

+8-1
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,7 @@
33
import sys
44
import threading
55
import time
6-
import rospy
6+
# import rospy
77
import importlib
88
import random
99

@@ -17,6 +17,13 @@
1717
from utils.traffic import TrafficManager
1818
from utils.constants import CARLA_TEST_SUITE_DIR, ROOT_PATH
1919

20+
ros_version = os.environ.get('ROS_VERSION', '2')
21+
if ros_version == '2':
22+
import rclpy
23+
from rclpy.node import Node
24+
else:
25+
import rospy
26+
2027
TESTSUITES = ROOT_PATH + '/' + CARLA_TEST_SUITE_DIR
2128

2229
def check_args(argv):

behavior_metrics/ui/gui/resources/worlds.json

+1-1
Original file line numberDiff line numberDiff line change
@@ -274,7 +274,7 @@
274274
"CARLA": [
275275
{
276276
"name": "Town01",
277-
"world": "/home/jderobot/carla-ros-bridge/catkin_ws/src/ros-bridge/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch",
277+
"world": "/home/canveo/carla_ws/ros-bridge/src/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch.py",
278278
"description": "Description"
279279
}
280280
]

behavior_metrics/ui/gui/views/toolbar.py

+9-4
Original file line numberDiff line numberDiff line change
@@ -89,7 +89,6 @@ def fill_topics(self):
8989
# topics = rospy.get_published_topics()
9090
if ros_version == '2':
9191
topics = self.node.get_topic_names_and_types()
92-
logger.info('Topics: ' + str(topics))
9392
else:
9493
topics = rospy.get_published_topics()
9594

@@ -288,7 +287,7 @@ def __init__(self, configuration, controller, parent=None, node=None):
288287
289288
Parameters:
290289
configuration {utils.configuration.Config} -- Configuration instance of the application
291-
controller {uitls.controller.Controller} -- Controller instance of the application
290+
controller {utils.controller.Controller} -- Controller instance of the application
292291
parent {ui.gui.views.main_view.MainView} -- Parent of this widget
293292
"""
294293
super(Toolbar, self).__init__(parent)
@@ -302,6 +301,8 @@ def __init__(self, configuration, controller, parent=None, node=None):
302301
self.parent = parent
303302
self.setFixedSize(self.windowsize)
304303
self.initUI()
304+
305+
print(f"controller: {controller.__class__}")
305306

306307
# Style of the widget
307308
self.setStyleSheet("""
@@ -520,7 +521,7 @@ def create_simulation_gb(self):
520521
with open(worlds_path) as f:
521522
data = f.read()
522523
worlds_dict = json.loads(data)[self.configuration.robot_type]
523-
524+
524525
sim_group = QGroupBox()
525526
sim_group.setTitle('Simulation')
526527
sim_layout = QGridLayout()
@@ -739,7 +740,7 @@ def load_brain(self):
739740
brain = self.brain_combobox.currentText() + '.py'
740741
txt = '<b><FONT COLOR = lightgreen>' + " ".join(self.brain_combobox.currentText().split("_")) + '</b>'
741742
prev_label_text = self.current_brain_label.text()
742-
743+
743744
try:
744745
self.current_brain_label.setText('Current brain: ' + txt)
745746

@@ -751,6 +752,10 @@ def load_brain(self):
751752
except Exception as ex:
752753
self.current_brain_label.setText(prev_label_text)
753754
print("Brain could not be loaded!.")
755+
print("brain_path: ", brains_path)
756+
print("robot_type: ", self.configuration.robot_type)
757+
print("brain: ", brain)
758+
754759
print(ex)
755760

756761
def load_world(self):

0 commit comments

Comments
 (0)