-
Notifications
You must be signed in to change notification settings - Fork 11
/
main.launch.py
197 lines (158 loc) · 4.92 KB
/
main.launch.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
from os import name, path, environ
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.actions import IncludeLaunchDescription
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.actions import ExecuteProcess
from launch.conditions import IfCondition
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node
from ament_index_python import get_package_share_directory
def generate_launch_description():
# leaderboard_liaison = Node(
# package='carla_interface',
# executable='liaison_node',
# parameters=[]
# )
lidar_processor = Node(
package='sensor_processing',
executable='lidar_processing_node'
)
mcl = Node(
package='state_estimation',
executable='mcl_node'
)
# carla_spawner = IncludeLaunchDescription(
# PythonLaunchDescriptionSource([get_package_share_directory(
# 'carla_spawn_objects'), '/carla_spawn_objects.launch.py']),
# launch_arguments={
# 'objects_definition_file': '/navigator/data/carla_objects.json'}.items(),
# )
# carla_controller = Node(
# package='carla_controller',
# executable='controller'
# )
urdf_publisher = Node(
package='robot_state_publisher',
executable='robot_state_publisher',
arguments=[path.join("/navigator/data", "hail_bopp.urdf")]
)
# carla_bridge_official = IncludeLaunchDescription(
# PythonLaunchDescriptionSource([get_package_share_directory(
# 'carla_ros_bridge'), '/carla_ros_bridge.launch.py']),
# launch_arguments={
# 'host': 'localhost',
# 'port': str(2000 + int(environ['ROS_DOMAIN_ID'])),
# 'synchronous_mode': 'True',
# 'town': 'Town02',
# 'register_all_sensors': 'False',
# 'ego_vehicle_role_name': 'hero',
# 'timeout': '30'
# }.items(),
# )
gnss_processor = Node(
package='state_estimation',
executable='gnss_processing_node'
)
mcl = Node(
package='state_estimation',
executable='mcl_node'
)
map_manager = Node(
package='map_management',
executable='map_management_node'
)
rviz = Node(
package='rviz2',
namespace='',
executable='rviz2',
name='rviz2',
arguments=['-d' + '/navigator/data/mcl.rviz']
)
ground_seg = Node(
package='occupancy_cpp',
executable='ground_segmentation_exe'
)
image_segmentation = Node(
package='segmentation',
executable='image_segmentation_node'
)
semantic_projection = Node(
package='segmentation',
executable='image_projection_node'
)
mcu_interface = Node(
package='mcu_interface',
executable='mcu_interface_node'
)
joy = Node(
package='joy_linux',
executable='joy_linux_node'
)
joy_translator = Node(
package='joy_translation',
executable='joy_translation_node'
)
epas = Node(
package='epas',
executable='epas_node'
)
linear_actuator = Node(
package='linear_actuator',
executable='linear_actuator_node'
)
controller = Node(
package="parade_controller",
executable="parade_controller_node"
)
left_lidar_driver = Node(
package = 'velodyne_driver',
executable = 'velodyne_driver_node',
parameters = ["/navigator/param/perception/lidar_driver_left.param.yaml"],
namespace='velo_left'
)
right_lidar_driver = Node(
package = 'velodyne_driver',
executable = 'velodyne_driver_node',
parameters = ["/navigator/param/perception/lidar_driver_right.param.yaml"],
namespace='velo_right'
)
left_lidar_pointcloud = Node(
package = 'velodyne_pointcloud',
executable = 'velodyne_convert_node',
parameters = ["/navigator/param/perception/lidar_pointcloud_left.param.yaml"],
namespace='velo_left'
)
right_lidar_pointcloud = Node(
package = 'velodyne_pointcloud',
executable = 'velodyne_convert_node',
parameters = ["/navigator/param/perception/lidar_pointcloud_right.param.yaml"],
namespace='velo_right'
)
camera = Node(
package = 'camera',
executable = 'camera_node'
)
gps_node = Node(
package = 'nmea_navsat_driver',
executable = 'nmea_serial_driver'
)
return LaunchDescription([
# CONTROL
# controller,
# INTERFACE
#joy,
#joy_translator,
#epas,
#mcu_interface,
#linear_actuator,
left_lidar_driver,
left_lidar_pointcloud,
right_lidar_driver,
right_lidar_pointcloud,
camera,
gps_node,
# MISC
urdf_publisher,
# rviz,
])