-
Notifications
You must be signed in to change notification settings - Fork 1
Expand file tree
/
Copy pathcommon.launch.py
More file actions
165 lines (147 loc) · 5.39 KB
/
common.launch.py
File metadata and controls
165 lines (147 loc) · 5.39 KB
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
import os
from ament_index_python.packages import get_package_share_directory
from launch.conditions import IfCondition, UnlessCondition
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.actions import IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
def generate_launch_description():
# ROS packages
pkg_phoenix_gazebo = get_package_share_directory('phoenix_gazebo')
pkg_phoenix_robot = get_package_share_directory('phoenix_robot')
pkg_robot_state_controller = get_package_share_directory(
'robot_state_controller')
pkg_isc_sick = get_package_share_directory('ros2_sick')
# Launch arguments
drive_mode_switch_button = LaunchConfiguration(
'drive_mode_switch_button', default='7')
use_sim_time = LaunchConfiguration('use_sim_time', default='false')
use_ai = LaunchConfiguration('use_ai', default='false')
state_publishers = IncludeLaunchDescription(
PythonLaunchDescriptionSource([
os.path.join(pkg_phoenix_gazebo, 'launch')
, '/include/state_publishers/state_publishers.launch.py'
]),
launch_arguments={'use_sim_time': use_sim_time}.items(),
)
ekf = IncludeLaunchDescription(
PythonLaunchDescriptionSource([
os.path.join(pkg_phoenix_robot, 'launch')
, '/include/robot_localization/robot_localization.launch.py'
]),
launch_arguments={'use_sim_time': use_sim_time}.items(),
)
robot_state_controller = IncludeLaunchDescription(
PythonLaunchDescriptionSource([
os.path.join(pkg_robot_state_controller, 'launch'),
'/robot_state_controller.launch.py'
]),
launch_arguments={
'switch_button': drive_mode_switch_button,
'init_value': 'teleop',
'use_sim_time': use_sim_time
}.items(),
)
camera = IncludeLaunchDescription(
PythonLaunchDescriptionSource([
os.path.join(pkg_phoenix_robot, 'launch'),
'/include/oakd/oakd.launch.py'
]),
launch_arguments={'use_sim_time': use_sim_time}.items(),
)
sick = IncludeLaunchDescription(
PythonLaunchDescriptionSource([
os.path.join(pkg_isc_sick, 'launch')
, '/sick.launch.py'
]),
launch_arguments={
'use_sim_time': use_sim_time,
'config_file': PathJoinSubstitution([pkg_phoenix_robot, 'config' ]) # , 'ros2_sick', 'sick_lms111.yaml'])
}.items(),
)
pir = IncludeLaunchDescription(
PythonLaunchDescriptionSource([
os.path.join(pkg_phoenix_robot, 'launch'),
'/include/phnx_io_ros/phnx_io_ros.launch.py'
]),
launch_arguments={'use_sim_time': use_sim_time}.items(),
)
pp = IncludeLaunchDescription(
PythonLaunchDescriptionSource([
os.path.join(pkg_phoenix_gazebo, 'launch'),
'/include/hybrid_pp/hybrid_pp.launch.py'
]),
launch_arguments={
'use_sim_time': use_sim_time,
'max_speed': '8.0',
'min_speed': '0.5'
}.items(),
)
obj_detector_ai = IncludeLaunchDescription(
PythonLaunchDescriptionSource([
os.path.join(pkg_phoenix_gazebo, 'launch'),
'/include/road_detectors/obj_detector_ai.launch.py'
]),
launch_arguments={
'use_sim_time': use_sim_time,
}.items(),
condition=IfCondition(use_ai)
)
obj_detector_cv = IncludeLaunchDescription(
PythonLaunchDescriptionSource([
os.path.join(pkg_phoenix_gazebo, 'launch'),
'/include/road_detectors/obj_detector_cv.launch.py'
]),
launch_arguments={
'use_sim_time': use_sim_time,
}.items(),
condition=UnlessCondition(use_ai)
)
poly_plan_ai = IncludeLaunchDescription(
PythonLaunchDescriptionSource([
os.path.join(pkg_phoenix_gazebo, 'launch'),
'/include/polynomial_planner/polynomial_planner_ai.launch.py'
]),
launch_arguments={
'use_sim_time': use_sim_time,
}.items(),
condition=IfCondition(use_ai)
)
poly_plan = IncludeLaunchDescription(
PythonLaunchDescriptionSource([
os.path.join(pkg_phoenix_gazebo, 'launch'),
'/include/polynomial_planner/polynomial_planner_ai.launch.py'
]),
launch_arguments={
'use_sim_time': use_sim_time,
}.items(),
condition=UnlessCondition(use_ai)
)
return LaunchDescription([
# Launch Arguments
DeclareLaunchArgument(
'drive_mode_switch_button',
default_value='10',
description='Which button is used on the joystick to switch drive mode. (In joy message)'
),
DeclareLaunchArgument(
'use_sim_time',
default_value='false',
description='Use simulation (Gazebo) clock if true'),
DeclareLaunchArgument(
'use_ai',
default_value='false',
description='Use ai stack if true'),
# Nodes
robot_state_controller,
state_publishers,
ekf,
camera,
pir,
pp,
obj_detector_ai,
obj_detector_cv,
poly_plan,
poly_plan_ai
])