Skip to content

Commit f9c59f0

Browse files
authored
Merge pull request #701 from canveo/issue-699
Issue 699
2 parents db2c655 + ab7100e commit f9c59f0

38 files changed

+1241
-187
lines changed

behavior_metrics/.gitignore

+3
Original file line numberDiff line numberDiff line change
@@ -119,3 +119,6 @@ dmypy.json
119119

120120
# Custom directories
121121
bags_analysis/
122+
behavior_metrics/
123+
behavior_metrics/carla-birdeye-view/
124+
carla-birdeye-view/

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:

behavior_metrics/carla-birdeye-view

-1
This file was deleted.
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,162 @@
1+
import os
2+
import launch
3+
from ament_index_python.packages import get_package_share_directory
4+
5+
def generate_launch_description():
6+
ld = launch.LaunchDescription([
7+
# Basic launch arguments
8+
launch.actions.DeclareLaunchArgument(
9+
name='host',
10+
default_value='localhost'
11+
),
12+
launch.actions.DeclareLaunchArgument(
13+
name='port',
14+
default_value='2000'
15+
),
16+
launch.actions.DeclareLaunchArgument(
17+
name='timeout',
18+
default_value='10'
19+
),
20+
launch.actions.DeclareLaunchArgument(
21+
name='role_name',
22+
default_value='ego_vehicle'
23+
),
24+
launch.actions.DeclareLaunchArgument(
25+
name='vehicle_filter',
26+
default_value='vehicle.*'
27+
),
28+
launch.actions.DeclareLaunchArgument(
29+
name='spawn_point',
30+
default_value='None'
31+
),
32+
launch.actions.DeclareLaunchArgument(
33+
name='town',
34+
default_value='Town01'
35+
),
36+
launch.actions.DeclareLaunchArgument(
37+
name='passive',
38+
default_value='False'
39+
),
40+
launch.actions.DeclareLaunchArgument(
41+
name='synchronous_mode_wait_for_vehicle_control_command',
42+
default_value='False'
43+
),
44+
launch.actions.DeclareLaunchArgument(
45+
name='fixed_delta_seconds',
46+
default_value='0.05'
47+
),
48+
# Weather condition launch arguments
49+
launch.actions.DeclareLaunchArgument(
50+
name='cloudiness',
51+
default_value='30.0' # Default cloudiness level
52+
),
53+
launch.actions.DeclareLaunchArgument(
54+
name='precipitation',
55+
default_value='30.0' # Default precipitation level
56+
),
57+
launch.actions.DeclareLaunchArgument(
58+
name='sun_altitude_angle',
59+
default_value='10.0' # Default sun altitude angle
60+
),
61+
launch.actions.DeclareLaunchArgument(
62+
name='sun_azimuth_angle',
63+
default_value='90.0' # Default sun azimuth angle
64+
),
65+
launch.actions.DeclareLaunchArgument(
66+
name='precipitation_deposits',
67+
default_value='20.0' # Default precipitation deposits level
68+
),
69+
launch.actions.DeclareLaunchArgument(
70+
name='wind_intensity',
71+
default_value='0.0' # Default wind intensity
72+
),
73+
launch.actions.DeclareLaunchArgument(
74+
name='fog_density',
75+
default_value='1.0' # Default fog density
76+
),
77+
launch.actions.DeclareLaunchArgument(
78+
name='wetness',
79+
default_value='0.0' # Default wetness level
80+
),
81+
# Log weather information for debugging
82+
launch.actions.LogInfo(
83+
msg=['Cloudiness: ', launch.substitutions.LaunchConfiguration('cloudiness')]
84+
),
85+
launch.actions.LogInfo(
86+
msg=['Precipitation: ', launch.substitutions.LaunchConfiguration('precipitation')]
87+
),
88+
launch.actions.LogInfo(
89+
msg=['Sun Altitude Angle: ', launch.substitutions.LaunchConfiguration('sun_altitude_angle')]
90+
),
91+
launch.actions.LogInfo(
92+
msg=['Sun Azimuth Angle: ', launch.substitutions.LaunchConfiguration('sun_azimuth_angle')]
93+
),
94+
launch.actions.LogInfo(
95+
msg=['Precipitation Deposits: ', launch.substitutions.LaunchConfiguration('precipitation_deposits')]
96+
),
97+
launch.actions.LogInfo(
98+
msg=['Wind Intensity: ', launch.substitutions.LaunchConfiguration('wind_intensity')]
99+
),
100+
launch.actions.LogInfo(
101+
msg=['Fog Density: ', launch.substitutions.LaunchConfiguration('fog_density')]
102+
),
103+
launch.actions.LogInfo(
104+
msg=['Wetness: ', launch.substitutions.LaunchConfiguration('wetness')]
105+
),
106+
# Include the carla_ros_bridge launch file
107+
# Propagate both the basic and weather parameters.
108+
launch.actions.IncludeLaunchDescription(
109+
launch.launch_description_sources.PythonLaunchDescriptionSource(
110+
os.path.join(get_package_share_directory('carla_ros_bridge'),
111+
'carla_ros_bridge.launch.py')
112+
),
113+
launch_arguments={
114+
'host': launch.substitutions.LaunchConfiguration('host'),
115+
'port': launch.substitutions.LaunchConfiguration('port'),
116+
'town': launch.substitutions.LaunchConfiguration('town'),
117+
'timeout': launch.substitutions.LaunchConfiguration('timeout'),
118+
'passive': launch.substitutions.LaunchConfiguration('passive'),
119+
'synchronous_mode_wait_for_vehicle_control_command': launch.substitutions.LaunchConfiguration('synchronous_mode_wait_for_vehicle_control_command'),
120+
'fixed_delta_seconds': launch.substitutions.LaunchConfiguration('fixed_delta_seconds'),
121+
# Pass weather parameters to carla_ros_bridge (if supported)
122+
'cloudiness': launch.substitutions.LaunchConfiguration('cloudiness'),
123+
'precipitation': launch.substitutions.LaunchConfiguration('precipitation'),
124+
'sun_altitude_angle': launch.substitutions.LaunchConfiguration('sun_altitude_angle'),
125+
'sun_azimuth_angle': launch.substitutions.LaunchConfiguration('sun_azimuth_angle'),
126+
'precipitation_deposits': launch.substitutions.LaunchConfiguration('precipitation_deposits'),
127+
'wind_intensity': launch.substitutions.LaunchConfiguration('wind_intensity'),
128+
'fog_density': launch.substitutions.LaunchConfiguration('fog_density'),
129+
'wetness': launch.substitutions.LaunchConfiguration('wetness')
130+
}.items()
131+
),
132+
# Include the carla_spawn_objects launch file
133+
launch.actions.IncludeLaunchDescription(
134+
launch.launch_description_sources.PythonLaunchDescriptionSource(
135+
os.path.join(get_package_share_directory('carla_spawn_objects'),
136+
'carla_example_ego_vehicle.launch.py')
137+
),
138+
launch_arguments={
139+
'host': launch.substitutions.LaunchConfiguration('host'),
140+
'port': launch.substitutions.LaunchConfiguration('port'),
141+
'timeout': launch.substitutions.LaunchConfiguration('timeout'),
142+
'vehicle_filter': launch.substitutions.LaunchConfiguration('vehicle_filter'),
143+
'role_name': launch.substitutions.LaunchConfiguration('role_name'),
144+
'spawn_point': launch.substitutions.LaunchConfiguration('spawn_point')
145+
}.items()
146+
),
147+
# Include the carla_manual_control launch file
148+
launch.actions.IncludeLaunchDescription(
149+
launch.launch_description_sources.PythonLaunchDescriptionSource(
150+
os.path.join(get_package_share_directory('carla_manual_control'),
151+
'carla_manual_control.launch.py')
152+
),
153+
launch_arguments={
154+
'role_name': launch.substitutions.LaunchConfiguration('role_name')
155+
}.items()
156+
)
157+
])
158+
return ld
159+
160+
if __name__ == '__main__':
161+
generate_launch_description()
162+
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+
])

0 commit comments

Comments
 (0)