39
40 """
41 Launch V2X subsystem nodes.
42 """
43
44 env_log_levels = EnvironmentVariable('CARMA_ROS_LOGGING_CONFIG', default_value='{ "default_level" : "WARN" }')
45
46 subsystem_controller_default_param_file = os.path.join(
47 get_package_share_directory('subsystem_controllers'), 'config/v2x_controller_config.yaml')
48
49 mobilitypath_publisher_param_file = os.path.join(
50 get_package_share_directory('mobilitypath_publisher'), 'config/parameters.yaml')
51
52 bsm_generator_param_file = os.path.join(
53 get_package_share_directory('bsm_generator'), 'config/parameters.yaml')
54
55 vehicle_characteristics_param_file = LaunchConfiguration('vehicle_characteristics_param_file')
56 declare_vehicle_characteristics_param_file_arg = DeclareLaunchArgument(
57 name = 'vehicle_characteristics_param_file',
58 default_value = "/opt/carma/vehicle/calibration/identifiers/UniqueVehicleParams.yaml",
59 description = "Path to file containing unique vehicle calibrations"
60 )
61
62
63 vehicle_config_param_file = LaunchConfiguration('vehicle_config_param_file')
64 declare_vehicle_config_param_file_arg = DeclareLaunchArgument(
65 name = 'vehicle_config_param_file',
66 default_value = "/opt/carma/vehicle/config/VehicleConfigParams.yaml",
67 description = "Path to file contain vehicle configuration parameters"
68 )
69
70 subsystem_controller_param_file = LaunchConfiguration('subsystem_controller_param_file')
71 declare_subsystem_controller_param_file_arg = DeclareLaunchArgument(
72 name = 'subsystem_controller_param_file',
73 default_value = subsystem_controller_default_param_file,
74 description = "Path to file containing override parameters for the subsystem controller"
75 )
76
77 vehicle_config_dir = LaunchConfiguration('vehicle_config_dir')
78 declare_vehicle_config_dir_arg = DeclareLaunchArgument(
79 name = 'vehicle_config_dir',
80 default_value = "/opt/carma/vehicle/config",
81 description = "Path to vehicle configuration directory populated by carma-config"
82 )
83
84
85
86 global_params_override_file = LaunchConfiguration('global_params_override_file')
87 declare_global_params_override_file_arg = DeclareLaunchArgument(
88 name = 'global_params_override_file',
89 default_value = [vehicle_config_dir, "/GlobalParamsOverride.yaml"],
90 description = "Path to global file containing the parameters overwrite"
91 )
92
93
94 enable_opening_tunnels = LaunchConfiguration('enable_opening_tunnels')
95 declare_enable_opening_tunnels = DeclareLaunchArgument(
96 name = 'enable_opening_tunnels',
97 default_value= 'True',
98 description='Flag to enable opening http tunnesl to CARMA Cloud'
99 )
100
101 carma_cloud_client_param_file = os.path.join(
102 get_package_share_directory('carma_cloud_client'), 'config/parameters.yaml')
103
104 use_sim_time = LaunchConfiguration('use_sim_time')
105 declare_use_sim_time_arg = DeclareLaunchArgument(
106 name = 'use_sim_time',
107 default_value = "False",
108 description = "True if simulation mode is on"
109 )
110
111
112 carma_v2x_container = ComposableNodeContainer(
113 package='carma_ros2_utils',
114 name='carma_v2x_container',
115 executable='carma_component_container_mt',
116 namespace=GetCurrentNamespace(),
117 composable_node_descriptions=[
118
119 ComposableNode(
120 package='mobilitypath_publisher',
121 plugin='mobilitypath_publisher::MobilityPathPublication',
122 name='mobilitypath_publisher_node',
123 extra_arguments=[
124 {'use_intra_process_comms': True},
125 {'--log-level' : GetLogLevel('mobilitypath_publisher', env_log_levels) }
126 ],
127 remappings=[
128 ("plan_trajectory", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/plan_trajectory" ] ),
129 ("guidance_state", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/state" ] ),
130 ("georeference", [ EnvironmentVariable('CARMA_LOCZ_NS', default_value=''), "/map_param_loader/georeference" ] ),
131 ("mobility_path_msg", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/outgoing_mobility_path" ] )
132 ],
133 parameters=[
134 mobilitypath_publisher_param_file,
135 vehicle_characteristics_param_file,
136 vehicle_config_param_file,
137 global_params_override_file
138 ]
139 ),
140 ComposableNode(
141 package='bsm_generator',
142 plugin='bsm_generator::BSMGenerator',
143 name='bsm_generator_node',
144 extra_arguments=[
145 {'use_intra_process_comms': True},
146 {'--log-level' : GetLogLevel('bsm_generator', env_log_levels) }
147 ],
148 remappings=[
149 ("velocity_accel_cov", [ EnvironmentVariable('CARMA_INTR_NS', default_value=''), "/velocity_accel_cov" ] ),
150 ("ekf_twist", [ EnvironmentVariable('CARMA_INTR_NS', default_value=''), "/vehicle/twist" ] ),
151 ("imu_raw", [ EnvironmentVariable('CARMA_INTR_NS', default_value=''), "/imu_raw" ] ),
152 ("transmission_state", [ EnvironmentVariable('CARMA_INTR_NS', default_value=''), "/can/transmission_state" ] ),
153 ("brake_position", [ EnvironmentVariable('CARMA_INTR_NS', default_value=''), "/can/brake_position" ] ),
154 ("steering_wheel_angle", [ EnvironmentVariable('CARMA_INTR_NS', default_value=''), "/can/steering_wheel_angle" ] ),
155 ("gnss_fix_fused", [ EnvironmentVariable('CARMA_INTR_NS', default_value=''), "/gnss_fix_fused" ] ),
156 ("pose", [ EnvironmentVariable('CARMA_LOCZ_NS', default_value=''), "/current_pose" ] ),
157 ("georeference", [ EnvironmentVariable('CARMA_LOCZ_NS', default_value=''), "/map_param_loader/georeference" ] )
158 ],
159 parameters=[
160 bsm_generator_param_file,
161 vehicle_characteristics_param_file,
162 vehicle_config_param_file,
163 global_params_override_file
164 ]
165 ),
166 ComposableNode(
167 package='cpp_message',
168 plugin='cpp_message::Node',
169 name='cpp_message_node',
170 extra_arguments=[
171 {'use_intra_process_comms': True},
172 {'--log-level' : GetLogLevel('cpp_message', env_log_levels) }
173 ],
174 remappings=[
175 ("inbound_binary_msg", [ EnvironmentVariable('CARMA_INTR_NS', default_value=''), "/comms/inbound_binary_msg" ] ),
176 ("outbound_binary_msg", [ EnvironmentVariable('CARMA_INTR_NS', default_value=''), "/comms/outbound_binary_msg" ] ),
177 ],
178 parameters=[
179 vehicle_config_param_file,
180 global_params_override_file
181 ]
182 ),
183 ComposableNode(
184 package='j2735_convertor',
185 plugin='j2735_convertor::Node',
186 name='j2735_convertor_node',
187 extra_arguments=[
188 {'use_intra_process_comms': True},
189 {'--log-level' : GetLogLevel('j2735_convertor', env_log_levels) }
190 ],
191 remappings=[
192 ("outgoing_bsm", "bsm_outbound" )
193 ],
194 parameters=[
195 vehicle_config_param_file,
196 global_params_override_file
197 ]
198 ),
199 ComposableNode(
200 package='carma_cloud_client',
201 plugin='carma_cloud_client::CarmaCloudClient',
202 name='carma_cloud_client_node',
203 extra_arguments=[
204 {'use_intra_process_comms': True},
205 {'--log-level' : GetLogLevel('carma_cloud_client', env_log_levels) }
206 ],
207 remappings=[
208 ("incoming_geofence_control", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/incoming_geofence_control" ] ),
209 ],
210 parameters = [
211 vehicle_config_param_file,
212 carma_cloud_client_param_file,
213 global_params_override_file
214 ]
215
216 ),
217 ]
218 )
219
220
221 subsystem_controller = Node(
222 package='subsystem_controllers',
223 name='v2x_controller',
224 executable='v2x_controller',
225 parameters=[
226 subsystem_controller_default_param_file,
227 subsystem_controller_param_file,
228 {"use_sim_time" : use_sim_time}],
229 on_exit= Shutdown(),
230 arguments=['--ros-args', '--log-level', GetLogLevel('subsystem_controllers', env_log_levels)]
231 )
232
233
234
235 REMOTE_USER="ubuntu"
236 REMOTE_ADDR="carma-cloud.com"
237 KEY_FILE="carma-cloud-1.pem"
238 HOST_PORT="33333"
239 REMOTE_PORT="22222"
240 param_launch_path = os.path.join(
241 get_package_share_directory('carma_cloud_client'), 'launch/scripts')
242
243 script = param_launch_path + '/open_tunnels.sh'
244
245 subprocess.check_call(['chmod','u+x', script])
246
247 key_path = "/opt/carma/vehicle/calibration/cloud_permission"
248
249 keyfile = key_path + '/' + KEY_FILE
250
251 subprocess.check_call(['sudo','chmod','400', keyfile])
252
253
254 open_tunnels_action = ExecuteProcess(
255
256 condition=IfCondition(enable_opening_tunnels),
257 cmd = ['sudo', script, '-u', REMOTE_USER, '-a', REMOTE_ADDR, '-k', keyfile, '-p', REMOTE_PORT, '-r', HOST_PORT],
258 output = 'screen'
259 )
260
261
262 return LaunchDescription([
263 declare_vehicle_config_param_file_arg,
264 declare_vehicle_config_dir_arg,
265 declare_global_params_override_file_arg,
266 declare_use_sim_time_arg,
267 declare_vehicle_characteristics_param_file_arg,
268 declare_subsystem_controller_param_file_arg,
269 declare_enable_opening_tunnels,
270 open_tunnels_action,
271 carma_v2x_container,
272 subsystem_controller
273 ])
def generate_launch_description()