Skip to content

Commit 99a4ea6

Browse files
authored
feat(tier4_control_launch): declare param path argument (autowarefoundation#1432)
Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
1 parent 4504ae1 commit 99a4ea6

File tree

1 file changed

+35
-40
lines changed

1 file changed

+35
-40
lines changed

launch/tier4_control_launch/launch/control.launch.py

+35-40
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,8 @@
1212
# See the License for the specific language governing permissions and
1313
# limitations under the License.
1414

15+
import os
16+
1517
import launch
1618
from launch.actions import DeclareLaunchArgument
1719
from launch.actions import GroupAction
@@ -33,26 +35,42 @@ def launch_setup(context, *args, **kwargs):
3335
vehicle_info_param_path = LaunchConfiguration("vehicle_info_param_file").perform(context)
3436
with open(vehicle_info_param_path, "r") as f:
3537
vehicle_info_param = yaml.safe_load(f)["/**"]["ros__parameters"]
36-
lat_controller_param_path = LaunchConfiguration("lat_controller_param_path").perform(context)
38+
39+
lat_controller_param_path = os.path.join(
40+
LaunchConfiguration("tier4_control_launch_param_path").perform(context),
41+
"trajectory_follower",
42+
"lateral_controller.param.yaml",
43+
)
3744
with open(lat_controller_param_path, "r") as f:
3845
lat_controller_param = yaml.safe_load(f)["/**"]["ros__parameters"]
39-
lon_controller_param_path = LaunchConfiguration("lon_controller_param_path").perform(context)
46+
47+
lon_controller_param_path = os.path.join(
48+
LaunchConfiguration("tier4_control_launch_param_path").perform(context),
49+
"trajectory_follower",
50+
"longitudinal_controller.param.yaml",
51+
)
4052
with open(lon_controller_param_path, "r") as f:
4153
lon_controller_param = yaml.safe_load(f)["/**"]["ros__parameters"]
42-
vehicle_cmd_gate_param_path = LaunchConfiguration("vehicle_cmd_gate_param_path").perform(
43-
context
54+
55+
vehicle_cmd_gate_param_path = os.path.join(
56+
LaunchConfiguration("tier4_control_launch_param_path").perform(context),
57+
"vehicle_cmd_gate",
58+
"vehicle_cmd_gate.param.yaml",
4459
)
4560
with open(vehicle_cmd_gate_param_path, "r") as f:
4661
vehicle_cmd_gate_param = yaml.safe_load(f)["/**"]["ros__parameters"]
62+
4763
lane_departure_checker_param_path = LaunchConfiguration(
4864
"lane_departure_checker_param_path"
4965
).perform(context)
5066
with open(lane_departure_checker_param_path, "r") as f:
5167
lane_departure_checker_param = yaml.safe_load(f)["/**"]["ros__parameters"]
5268

53-
operation_mode_transition_manager_param_path = LaunchConfiguration(
54-
"operation_mode_transition_manager_param_path"
55-
).perform(context)
69+
operation_mode_transition_manager_param_path = os.path.join(
70+
LaunchConfiguration("tier4_control_launch_param_path").perform(context),
71+
"operation_mode_transition_manager",
72+
"operation_mode_transition_manager.param.yaml",
73+
)
5674
with open(operation_mode_transition_manager_param_path, "r") as f:
5775
operation_mode_transition_manager_param = yaml.safe_load(f)["/**"]["ros__parameters"]
5876

@@ -247,8 +265,17 @@ def add_launch_arg(name: str, default_value=None, description=None):
247265
DeclareLaunchArgument(name, default_value=default_value, description=description)
248266
)
249267

250-
# lateral controller
268+
# parameter
269+
add_launch_arg(
270+
"tier4_control_launch_param_path",
271+
[
272+
FindPackageShare("tier4_control_launch"),
273+
"/config",
274+
],
275+
"tier4_control_launch parameter path",
276+
)
251277

278+
# lateral controller
252279
add_launch_arg(
253280
"lateral_controller_mode",
254281
"mpc_follower",
@@ -264,42 +291,10 @@ def add_launch_arg(name: str, default_value=None, description=None):
264291
"path to the parameter file of vehicle information",
265292
)
266293

267-
add_launch_arg(
268-
"lat_controller_param_path",
269-
[
270-
FindPackageShare("tier4_control_launch"),
271-
"/config/trajectory_follower/lateral_controller.param.yaml",
272-
],
273-
"path to the parameter file of lateral controller",
274-
)
275-
add_launch_arg(
276-
"lon_controller_param_path",
277-
[
278-
FindPackageShare("tier4_control_launch"),
279-
"/config/trajectory_follower/longitudinal_controller.param.yaml",
280-
],
281-
"path to the parameter file of longitudinal controller",
282-
)
283-
add_launch_arg(
284-
"vehicle_cmd_gate_param_path",
285-
[
286-
FindPackageShare("tier4_control_launch"),
287-
"/config/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml",
288-
],
289-
"path to the parameter file of vehicle_cmd_gate",
290-
)
291294
add_launch_arg(
292295
"lane_departure_checker_param_path",
293296
[FindPackageShare("lane_departure_checker"), "/config/lane_departure_checker.param.yaml"],
294297
)
295-
add_launch_arg(
296-
"operation_mode_transition_manager_param_path",
297-
[
298-
FindPackageShare("tier4_control_launch"),
299-
"/config/operation_mode_transition_manager/operation_mode_transition_manager.param.yaml",
300-
],
301-
"path to the parameter file of vehicle_cmd_gate",
302-
)
303298

304299
# velocity controller
305300
add_launch_arg("show_debug_info", "false", "show debug information")

0 commit comments

Comments
 (0)