From c192ab84d7bfd309e734939d02add1dbcd4c8f8b Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 20 Jan 2023 12:38:15 +0900 Subject: [PATCH] refactor(autoware_launch): remove control_launch, and use tier4_control_launch instead (#700) * refactor(autoware_launch): remove control_launch, and use tier4_control_launch instead Signed-off-by: Takayuki Murooka * remove control_launch Signed-off-by: Takayuki Murooka * ci(pre-commit): autofix * ci(pre-commit): autofix Signed-off-by: Takayuki Murooka Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../control}/common/nearest_search.param.yaml | 0 .../external_cmd_selector.param.yaml | 4 + .../lane_departure_checker.param.yaml | 15 + .../obstacle_collision_checker.param.yaml | 11 + ...eration_mode_transition_manager.param.yaml | 0 .../shift_decider/shift_decider.param.yaml | 0 .../lateral/mpc.param.yaml | 0 .../lateral/pure_pursuit.param.yaml | 16 + .../longitudinal/pid.param.yaml | 0 .../trajectory_follower_node.param.yaml | 0 .../vehicle_cmd_gate.param.yaml | 3 + autoware_launch/launch/autoware.launch.xml | 12 +- .../tier4_control_component.launch.xml | 45 ++ .../launch/planning_simulator.launch.xml | 2 - autoware_launch/package.xml | 2 +- control_launch/CMakeLists.txt | 23 - control_launch/README.md | 24 - .../lateral/pure_pursuit.param.yaml | 9 - control_launch/control_launch.drawio.svg | 421 ------------------ control_launch/launch/control.launch.py | 382 ---------------- control_launch/launch/control.launch.xml | 23 - control_launch/package.xml | 26 -- 22 files changed, 100 insertions(+), 918 deletions(-) rename {control_launch/config => autoware_launch/config/control}/common/nearest_search.param.yaml (100%) create mode 100644 autoware_launch/config/control/external_cmd_selector/external_cmd_selector.param.yaml create mode 100644 autoware_launch/config/control/lane_departure_checker/lane_departure_checker.param.yaml create mode 100644 autoware_launch/config/control/obstacle_collision_checker/obstacle_collision_checker.param.yaml rename {control_launch/config => autoware_launch/config/control}/operation_mode_transition_manager/operation_mode_transition_manager.param.yaml (100%) rename {control_launch/config => autoware_launch/config/control}/shift_decider/shift_decider.param.yaml (100%) rename {control_launch/config => autoware_launch/config/control}/trajectory_follower/lateral/mpc.param.yaml (100%) create mode 100644 autoware_launch/config/control/trajectory_follower/lateral/pure_pursuit.param.yaml rename {control_launch/config => autoware_launch/config/control}/trajectory_follower/longitudinal/pid.param.yaml (100%) rename {control_launch/config => autoware_launch/config/control}/trajectory_follower/trajectory_follower_node.param.yaml (100%) rename {control_launch/config => autoware_launch/config/control}/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml (84%) create mode 100644 autoware_launch/launch/components/tier4_control_component.launch.xml delete mode 100644 control_launch/CMakeLists.txt delete mode 100644 control_launch/README.md delete mode 100644 control_launch/config/trajectory_follower/lateral/pure_pursuit.param.yaml delete mode 100644 control_launch/control_launch.drawio.svg delete mode 100644 control_launch/launch/control.launch.py delete mode 100644 control_launch/launch/control.launch.xml delete mode 100644 control_launch/package.xml diff --git a/control_launch/config/common/nearest_search.param.yaml b/autoware_launch/config/control/common/nearest_search.param.yaml similarity index 100% rename from control_launch/config/common/nearest_search.param.yaml rename to autoware_launch/config/control/common/nearest_search.param.yaml diff --git a/autoware_launch/config/control/external_cmd_selector/external_cmd_selector.param.yaml b/autoware_launch/config/control/external_cmd_selector/external_cmd_selector.param.yaml new file mode 100644 index 0000000000..6556656cc8 --- /dev/null +++ b/autoware_launch/config/control/external_cmd_selector/external_cmd_selector.param.yaml @@ -0,0 +1,4 @@ +/**: + ros__parameters: + update_rate: 10.0 + initial_selector_mode: "local" # ["local", "remote"] diff --git a/autoware_launch/config/control/lane_departure_checker/lane_departure_checker.param.yaml b/autoware_launch/config/control/lane_departure_checker/lane_departure_checker.param.yaml new file mode 100644 index 0000000000..092a6765aa --- /dev/null +++ b/autoware_launch/config/control/lane_departure_checker/lane_departure_checker.param.yaml @@ -0,0 +1,15 @@ +/**: + ros__parameters: + # Node + update_rate: 10.0 + visualize_lanelet: false + + # Core + footprint_margin_scale: 1.0 + resample_interval: 0.3 + max_deceleration: 2.8 + delay_time: 1.3 + max_lateral_deviation: 2.0 + max_longitudinal_deviation: 2.0 + max_yaw_deviation_deg: 60.0 + delta_yaw_threshold_for_closest_point: 1.570 #M_PI/2.0, delta yaw thres for closest point diff --git a/autoware_launch/config/control/obstacle_collision_checker/obstacle_collision_checker.param.yaml b/autoware_launch/config/control/obstacle_collision_checker/obstacle_collision_checker.param.yaml new file mode 100644 index 0000000000..e3c78c90e2 --- /dev/null +++ b/autoware_launch/config/control/obstacle_collision_checker/obstacle_collision_checker.param.yaml @@ -0,0 +1,11 @@ +/**: + ros__parameters: + # Node + update_rate: 10.0 + + # Core + delay_time: 0.03 # delay time of vehicle [s] + footprint_margin: 0.0 # margin for footprint [m] + max_deceleration: 1.5 # max deceleration [m/ss] + resample_interval: 0.3 # interval distance to resample point cloud [m] + search_radius: 5.0 # search distance from trajectory to point cloud [m] diff --git a/control_launch/config/operation_mode_transition_manager/operation_mode_transition_manager.param.yaml b/autoware_launch/config/control/operation_mode_transition_manager/operation_mode_transition_manager.param.yaml similarity index 100% rename from control_launch/config/operation_mode_transition_manager/operation_mode_transition_manager.param.yaml rename to autoware_launch/config/control/operation_mode_transition_manager/operation_mode_transition_manager.param.yaml diff --git a/control_launch/config/shift_decider/shift_decider.param.yaml b/autoware_launch/config/control/shift_decider/shift_decider.param.yaml similarity index 100% rename from control_launch/config/shift_decider/shift_decider.param.yaml rename to autoware_launch/config/control/shift_decider/shift_decider.param.yaml diff --git a/control_launch/config/trajectory_follower/lateral/mpc.param.yaml b/autoware_launch/config/control/trajectory_follower/lateral/mpc.param.yaml similarity index 100% rename from control_launch/config/trajectory_follower/lateral/mpc.param.yaml rename to autoware_launch/config/control/trajectory_follower/lateral/mpc.param.yaml diff --git a/autoware_launch/config/control/trajectory_follower/lateral/pure_pursuit.param.yaml b/autoware_launch/config/control/trajectory_follower/lateral/pure_pursuit.param.yaml new file mode 100644 index 0000000000..0b8b464e9f --- /dev/null +++ b/autoware_launch/config/control/trajectory_follower/lateral/pure_pursuit.param.yaml @@ -0,0 +1,16 @@ +/**: + ros__parameters: + ld_velocity_ratio: 2.4 + ld_lateral_error_ratio: 3.6 + ld_curvature_ratio: 120.0 + long_ld_lateral_error_threshold: 0.5 + min_lookahead_distance: 4.35 + max_lookahead_distance: 15.0 + converged_steer_rad: 0.1 + reverse_min_lookahead_distance: 7.0 + prediction_ds: 0.3 + prediction_distance_length: 21.0 + resampling_ds: 0.1 + curvature_calculation_distance: 4.0 + enable_path_smoothing: false + path_filter_moving_ave_num: 25 diff --git a/control_launch/config/trajectory_follower/longitudinal/pid.param.yaml b/autoware_launch/config/control/trajectory_follower/longitudinal/pid.param.yaml similarity index 100% rename from control_launch/config/trajectory_follower/longitudinal/pid.param.yaml rename to autoware_launch/config/control/trajectory_follower/longitudinal/pid.param.yaml diff --git a/control_launch/config/trajectory_follower/trajectory_follower_node.param.yaml b/autoware_launch/config/control/trajectory_follower/trajectory_follower_node.param.yaml similarity index 100% rename from control_launch/config/trajectory_follower/trajectory_follower_node.param.yaml rename to autoware_launch/config/control/trajectory_follower/trajectory_follower_node.param.yaml diff --git a/control_launch/config/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml b/autoware_launch/config/control/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml similarity index 84% rename from control_launch/config/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml rename to autoware_launch/config/control/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml index 351ad877e1..1a1d807858 100644 --- a/control_launch/config/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml +++ b/autoware_launch/config/control/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml @@ -2,6 +2,9 @@ ros__parameters: update_rate: 10.0 system_emergency_heartbeat_timeout: 0.5 + use_emergency_handling: false + check_external_emergency_heartbeat: false + use_start_request: false external_emergency_stop_heartbeat_timeout: 0.0 stop_hold_acceleration: -1.5 emergency_acceleration: -2.4 diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index aaeaa13d39..f964f2da2b 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -35,8 +35,6 @@ - - @@ -120,13 +118,13 @@ - - + + + + - - - + diff --git a/autoware_launch/launch/components/tier4_control_component.launch.xml b/autoware_launch/launch/components/tier4_control_component.launch.xml new file mode 100644 index 0000000000..264deb0ffc --- /dev/null +++ b/autoware_launch/launch/components/tier4_control_component.launch.xml @@ -0,0 +1,45 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index 77e13311cc..62fc034a6e 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -47,8 +47,6 @@ - - diff --git a/autoware_launch/package.xml b/autoware_launch/package.xml index 7b17634425..eaa526cead 100644 --- a/autoware_launch/package.xml +++ b/autoware_launch/package.xml @@ -11,7 +11,6 @@ ament_cmake_auto ad_api_adaptors - control_launch global_parameter_loader planning_launch python3-bson @@ -19,6 +18,7 @@ rviz2 system_launch tier4_autoware_api_launch + tier4_control_launch tier4_localization_launch tier4_map_launch tier4_perception_launch diff --git a/control_launch/CMakeLists.txt b/control_launch/CMakeLists.txt deleted file mode 100644 index 206bb55e10..0000000000 --- a/control_launch/CMakeLists.txt +++ /dev/null @@ -1,23 +0,0 @@ -cmake_minimum_required(VERSION 3.5) -project(control_launch) - -if(NOT CMAKE_CXX_STANDARD) - set(CMAKE_CXX_STANDARD 14) -endif() -if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") - add_compile_options(-Wno-unused-parameter -Wall -Wextra -Wpedantic) -endif() - -find_package(ament_cmake_auto REQUIRED) -ament_auto_find_build_dependencies() - -if(BUILD_TESTING) - find_package(ament_lint_auto REQUIRED) - ament_lint_auto_find_test_dependencies() -endif() - -ament_auto_package( - INSTALL_TO_SHARE - config - launch -) diff --git a/control_launch/README.md b/control_launch/README.md deleted file mode 100644 index f18eedc3c9..0000000000 --- a/control_launch/README.md +++ /dev/null @@ -1,24 +0,0 @@ -# control_launch - -## Structure - -![control_launch](./control_launch.drawio.svg) - -## Package Dependencies - -Please see `` in `package.xml`. - -## Usage - -You can include as follows in `*.launch.xml` to use `control.launch.py`. - -```xml - - - - -``` - -## Notes - -For reducing processing load, we use the [Component](https://docs.ros.org/en/galactic/Concepts/About-Composition.html) feature in ROS2 (similar to Nodelet in ROS1 ) diff --git a/control_launch/config/trajectory_follower/lateral/pure_pursuit.param.yaml b/control_launch/config/trajectory_follower/lateral/pure_pursuit.param.yaml deleted file mode 100644 index acbb3a85a3..0000000000 --- a/control_launch/config/trajectory_follower/lateral/pure_pursuit.param.yaml +++ /dev/null @@ -1,9 +0,0 @@ -/**: - ros__parameters: - # -- system -- - control_period: 0.033 - - # --algorithm -- - lookahead_distance_ratio: 2.2 - min_lookahead_distance: 2.5 - reverse_min_lookahead_distance: 7.0 diff --git a/control_launch/control_launch.drawio.svg b/control_launch/control_launch.drawio.svg deleted file mode 100644 index f51b6ba126..0000000000 --- a/control_launch/control_launch.drawio.svg +++ /dev/null @@ -1,421 +0,0 @@ - - - - - - - -
-
-
- container -
-
-
- - package: rclcpp_components - -
-
-
-
-
- - container... - -
-
- - - - -
-
-
- control.launch.py -
-
-
- - package: control_launch - -
-
-
-
-
- - control.launch.py... - -
-
- - - - - - - -
-
-
- mpc_follower -
-
-
-
- - mpc_follower - -
-
- - - - - -
-
-
- pure_pursuit -
-
-
-
- - pure_pursuit - -
-
- - - - -
-
-
- $(var lateral_controller_mode) -
-
-
-
- - $(var lateral_controller_mode) - -
-
- - - - -
-
-
- launch name -
-
-
- - package: package name - -
-
-
-
-
- - launch name... - -
-
- - - - -
-
-
- ex: -
-
-
-
- - ex: - -
-
- - - - -
-
-
- node name -
-
-
- - package: package name - -
-
-
-
-
- - node name... - -
-
- - - - -
-
-
- latlon_muxer -
-
-
- - package: latlon_muxer - -
-
-
-
-
- - latlon_muxer... - -
-
- - - - -
-
-
- mpc_follower -
-
-
- - package: mpc_follower - -
-
-
-
-
- - mpc_follower... - -
-
- - - - -
-
-
- pure_pursuit -
-
-
- - package: pure_pursuit - -
-
-
-
-
- - pure_pursuit... - -
-
- - - - -
-
-
- velocity_controller -
-
-
- - package: velocity_controller - -
-
-
-
-
- - velocity_controller... - -
-
- - - - -
-
-
- lane_departure_checker_node -
-
-
- - package: lane_departure_checker_node - -
-
-
-
-
- - lane_departure_checker_node... - -
-
- - - - -
-
-
- shift_decider -
-
-
- - package: shift_decider - -
-
-
-
-
- - shift_decider... - -
-
- - - - -
-
-
- vehicle_cmd_gate -
-
-
- - package: vehicle_cmd_gate - -
-
-
-
-
- - vehicle_cmd_gate... - -
-
- - - - -
-
-
- external_cmd_converter -
-
-
- - package: external_cmd_converter - -
-
-
-
-
- - external_cmd_converter... - -
-
- - - - -
-
-
- external_cmd_selector -
-
-
- - package: external_cmd_selector - -
-
-
-
-
- - external_cmd_selector... - -
-
- - - - -
-
-
- other name -
-
-
- - package: package name - -
-
-
-
-
- - other name... - -
-
-
- - - - - Viewer does not support full SVG 1.1 - - - -
diff --git a/control_launch/launch/control.launch.py b/control_launch/launch/control.launch.py deleted file mode 100644 index 0dc4d1e836..0000000000 --- a/control_launch/launch/control.launch.py +++ /dev/null @@ -1,382 +0,0 @@ -# Copyright 2020 Tier IV, Inc. All rights reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -import launch -from launch.actions import DeclareLaunchArgument -from launch.actions import GroupAction -from launch.actions import IncludeLaunchDescription -from launch.actions import OpaqueFunction -from launch.actions import SetLaunchConfiguration -from launch.conditions import IfCondition -from launch.conditions import UnlessCondition -from launch.launch_description_sources import PythonLaunchDescriptionSource -from launch.substitutions import LaunchConfiguration -from launch_ros.actions import ComposableNodeContainer -from launch_ros.actions import PushRosNamespace -from launch_ros.descriptions import ComposableNode -from launch_ros.substitutions import FindPackageShare -import yaml - - -def launch_setup(context, *args, **kwargs): - nearest_search_param_path = LaunchConfiguration("nearest_search_param_path").perform(context) - with open(nearest_search_param_path, "r") as f: - nearest_search_param = yaml.safe_load(f)["/**"]["ros__parameters"] - lat_controller_param_path = LaunchConfiguration("lat_controller_param_path").perform(context) - with open(lat_controller_param_path, "r") as f: - lat_controller_param = yaml.safe_load(f)["/**"]["ros__parameters"] - lon_controller_param_path = LaunchConfiguration("lon_controller_param_path").perform(context) - with open(lon_controller_param_path, "r") as f: - lon_controller_param = yaml.safe_load(f)["/**"]["ros__parameters"] - trajectory_follower_node_param_path = LaunchConfiguration( - "trajectory_follower_node_param_path" - ).perform(context) - with open(trajectory_follower_node_param_path, "r") as f: - trajectory_follower_node_param = yaml.safe_load(f)["/**"]["ros__parameters"] - vehicle_cmd_gate_param_path = LaunchConfiguration("vehicle_cmd_gate_param_path").perform( - context - ) - with open(vehicle_cmd_gate_param_path, "r") as f: - vehicle_cmd_gate_param = yaml.safe_load(f)["/**"]["ros__parameters"] - lane_departure_checker_param_path = LaunchConfiguration( - "lane_departure_checker_param_path" - ).perform(context) - with open(lane_departure_checker_param_path, "r") as f: - lane_departure_checker_param = yaml.safe_load(f)["/**"]["ros__parameters"] - - operation_mode_transition_manager_param_path = LaunchConfiguration( - "operation_mode_transition_manager_param_path" - ).perform(context) - with open(operation_mode_transition_manager_param_path, "r") as f: - operation_mode_transition_manager_param = yaml.safe_load(f)["/**"]["ros__parameters"] - - shift_decider_param_path = LaunchConfiguration("shift_decider_param_path").perform(context) - with open(shift_decider_param_path, "r") as f: - shift_decider_param = yaml.safe_load(f)["/**"]["ros__parameters"] - - controller_component = ComposableNode( - package="trajectory_follower_node", - plugin="autoware::motion::control::trajectory_follower_node::Controller", - name="controller_node_exe", - namespace="trajectory_follower", - remappings=[ - ("~/input/reference_trajectory", "/planning/scenario_planning/trajectory"), - ("~/input/current_odometry", "/localization/kinematic_state"), - ("~/input/current_steering", "/vehicle/status/steering_status"), - ("~/input/current_accel", "/localization/acceleration"), - ("~/output/predicted_trajectory", "lateral/predicted_trajectory"), - ("~/output/lateral_diagnostic", "lateral/diagnostic"), - ("~/output/slope_angle", "longitudinal/slope_angle"), - ("~/output/longitudinal_diagnostic", "longitudinal/diagnostic"), - ("~/output/control_cmd", "control_cmd"), - ], - parameters=[ - { - "ctrl_period": 0.03, - "lateral_controller_mode": LaunchConfiguration("lateral_controller_mode"), - "longitudinal_controller_mode": LaunchConfiguration("longitudinal_controller_mode"), - }, - nearest_search_param, - trajectory_follower_node_param, - lon_controller_param, - lat_controller_param, - ], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - - # lane departure checker - lane_departure_component = ComposableNode( - package="lane_departure_checker", - plugin="lane_departure_checker::LaneDepartureCheckerNode", - name="lane_departure_checker_node", - namespace="trajectory_follower", - remappings=[ - ("~/input/odometry", "/localization/kinematic_state"), - ("~/input/lanelet_map_bin", "/map/vector_map"), - ("~/input/route", "/planning/mission_planning/route"), - ("~/input/reference_trajectory", "/planning/scenario_planning/trajectory"), - ( - "~/input/predicted_trajectory", - "/control/trajectory_follower/lateral/predicted_trajectory", - ), - ], - parameters=[nearest_search_param, lane_departure_checker_param], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - - # shift decider - shift_decider_component = ComposableNode( - package="shift_decider", - plugin="ShiftDecider", - name="shift_decider", - remappings=[ - ("input/control_cmd", "/control/trajectory_follower/control_cmd"), - ("input/state", "/autoware/state"), - ("output/gear_cmd", "/control/shift_decider/gear_cmd"), - ], - parameters=[ - shift_decider_param, - ], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - - # vehicle cmd gate - vehicle_cmd_gate_component = ComposableNode( - package="vehicle_cmd_gate", - plugin="vehicle_cmd_gate::VehicleCmdGate", - name="vehicle_cmd_gate", - remappings=[ - ("input/emergency_state", "/system/emergency/emergency_state"), - ("input/steering", "/vehicle/status/steering_status"), - ("input/operation_mode", "/system/operation_mode/state"), - ("input/auto/control_cmd", "/control/trajectory_follower/control_cmd"), - ("input/auto/turn_indicators_cmd", "/planning/turn_indicators_cmd"), - ("input/auto/hazard_lights_cmd", "/planning/hazard_lights_cmd"), - ("input/auto/gear_cmd", "/control/shift_decider/gear_cmd"), - ("input/external/control_cmd", "/external/selected/control_cmd"), - ("input/external/turn_indicators_cmd", "/external/selected/turn_indicators_cmd"), - ("input/external/hazard_lights_cmd", "/external/selected/hazard_lights_cmd"), - ("input/external/gear_cmd", "/external/selected/gear_cmd"), - ("input/external_emergency_stop_heartbeat", "/external/selected/heartbeat"), - ("input/gate_mode", "/control/gate_mode_cmd"), - ("input/emergency/control_cmd", "/system/emergency/control_cmd"), - ("input/emergency/hazard_lights_cmd", "/system/emergency/hazard_lights_cmd"), - ("input/emergency/gear_cmd", "/system/emergency/gear_cmd"), - ("input/mrm_state", "/system/fail_safe/mrm_state"), - ("output/vehicle_cmd_emergency", "/control/command/emergency_cmd"), - ("output/control_cmd", "/control/command/control_cmd"), - ("output/gear_cmd", "/control/command/gear_cmd"), - ("output/turn_indicators_cmd", "/control/command/turn_indicators_cmd"), - ("output/hazard_lights_cmd", "/control/command/hazard_lights_cmd"), - ("output/gate_mode", "/control/current_gate_mode"), - ("output/engage", "/api/autoware/get/engage"), - ("output/external_emergency", "/api/autoware/get/emergency"), - ("output/operation_mode", "/control/vehicle_cmd_gate/operation_mode"), - ("~/service/engage", "/api/autoware/set/engage"), - ("~/service/external_emergency", "/api/autoware/set/emergency"), - # TODO(Takagi, Isamu): deprecated - ("input/engage", "/autoware/engage"), - ("~/service/external_emergency_stop", "~/external_emergency_stop"), - ("~/service/clear_external_emergency_stop", "~/clear_external_emergency_stop"), - ], - parameters=[ - vehicle_cmd_gate_param, - { - "use_emergency_handling": LaunchConfiguration("use_emergency_handling"), - "check_external_emergency_heartbeat": LaunchConfiguration( - "check_external_emergency_heartbeat" - ), - "use_start_request": LaunchConfiguration("use_start_request"), - }, - ], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - - # operation mode transition manager - operation_mode_transition_manager_component = ComposableNode( - package="operation_mode_transition_manager", - plugin="operation_mode_transition_manager::OperationModeTransitionManager", - name="operation_mode_transition_manager", - remappings=[ - # input - ("kinematics", "/localization/kinematic_state"), - ("steering", "/vehicle/status/steering_status"), - ("trajectory", "/planning/scenario_planning/trajectory"), - ("control_cmd", "/control/command/control_cmd"), - ("control_mode_report", "/vehicle/status/control_mode"), - ("gate_operation_mode", "/control/vehicle_cmd_gate/operation_mode"), - # output - ("is_autonomous_available", "/control/is_autonomous_available"), - ("control_mode_request", "/control/control_mode_request"), - ], - parameters=[ - nearest_search_param, - operation_mode_transition_manager_param, - ], - ) - - # external cmd selector - external_cmd_selector_loader = IncludeLaunchDescription( - PythonLaunchDescriptionSource( - [FindPackageShare("external_cmd_selector"), "/launch/external_cmd_selector.launch.py"] - ), - launch_arguments=[ - ("use_intra_process", LaunchConfiguration("use_intra_process")), - ("target_container", "/control/control_container"), - # This is temporary uncomment. I will replace control_launch with tier4_control_launch soon. - # ("initial_selector_mode", LaunchConfiguration("initial_selector_mode")), - ( - "external_cmd_selector_param_path", - LaunchConfiguration("external_cmd_selector_param_path"), - ), - ], - ) - - # external cmd converter - external_cmd_converter_loader = IncludeLaunchDescription( - PythonLaunchDescriptionSource( - [FindPackageShare("external_cmd_converter"), "/launch/external_cmd_converter.launch.py"] - ), - launch_arguments=[ - ("use_intra_process", LaunchConfiguration("use_intra_process")), - ("target_container", "/control/control_container"), - ], - ) - - container = ComposableNodeContainer( - name="control_container", - namespace="", - package="rclcpp_components", - executable=LaunchConfiguration("container_executable"), - composable_node_descriptions=[ - controller_component, - lane_departure_component, - shift_decider_component, - vehicle_cmd_gate_component, - operation_mode_transition_manager_component, - ], - ) - - group = GroupAction( - [ - PushRosNamespace("control"), - container, - external_cmd_selector_loader, - external_cmd_converter_loader, - ] - ) - - return [group] - - -def generate_launch_description(): - launch_arguments = [] - - def add_launch_arg(name: str, default_value=None, description=None): - launch_arguments.append( - DeclareLaunchArgument(name, default_value=default_value, description=description) - ) - - # lateral controller mode - add_launch_arg( - "lateral_controller_mode", - "mpc", - "lateral controller mode: `mpc` or `pure_pursuit`", - ) - - # longitudinal controller mode - add_launch_arg( - "longitudinal_controller_mode", - "pid", - "longitudinal controller mode: `pid`", - ) - - # parameter file path - add_launch_arg( - "nearest_search_param_path", - [ - FindPackageShare("control_launch"), - "/config/common/nearest_search.param.yaml", - ], - "path to the parameter file of nearest search", - ) - add_launch_arg( - "lat_controller_param_path", - [ - FindPackageShare("control_launch"), - "/config/trajectory_follower/lateral/mpc.param.yaml", - ], - "path to the parameter file of lateral controller. default is `mpc_follower`", - ) - add_launch_arg( - "lon_controller_param_path", - [ - FindPackageShare("control_launch"), - "/config/trajectory_follower/longitudinal/pid.param.yaml", - ], - "path to the parameter file of longitudinal controller", - ) - add_launch_arg( - "trajectory_follower_node_param_path", - [ - FindPackageShare("control_launch"), - "/config/trajectory_follower/trajectory_follower_node.param.yaml", - ], - "path to the parameter file of longitudinal controller", - ) - add_launch_arg( - "vehicle_cmd_gate_param_path", - [ - FindPackageShare("control_launch"), - "/config/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml", - ], - "path to the parameter file of vehicle_cmd_gate", - ) - add_launch_arg( - "lane_departure_checker_param_path", - [FindPackageShare("lane_departure_checker"), "/config/lane_departure_checker.param.yaml"], - ) - add_launch_arg( - "operation_mode_transition_manager_param_path", - [ - FindPackageShare("control_launch"), - "/config/operation_mode_transition_manager/operation_mode_transition_manager.param.yaml", - ], - "path to the parameter file of vehicle_cmd_gate", - ) - add_launch_arg( - "shift_decider_param_path", - [ - FindPackageShare("control_launch"), - "/config/shift_decider/shift_decider.param.yaml", - ], - "path to the parameter file of shift_decider", - ) - - # vehicle cmd gate - add_launch_arg("use_emergency_handling", "false", "use emergency handling") - add_launch_arg("check_external_emergency_heartbeat", "true", "use external emergency stop") - add_launch_arg("use_start_request", "false", "use start request service") - - # external cmd selector - add_launch_arg("initial_selector_mode", "remote", "local or remote") - add_launch_arg( - "external_cmd_selector_param_path", - [ - FindPackageShare("external_cmd_selector"), - "/config/external_cmd_selector.param.yaml", - ], - ) - - # component - add_launch_arg("use_intra_process", "false", "use ROS2 component container communication") - add_launch_arg("use_multithread", "false", "use multithread") - set_container_executable = SetLaunchConfiguration( - "container_executable", - "component_container", - condition=UnlessCondition(LaunchConfiguration("use_multithread")), - ) - set_container_mt_executable = SetLaunchConfiguration( - "container_executable", - "component_container_mt", - condition=IfCondition(LaunchConfiguration("use_multithread")), - ) - return launch.LaunchDescription( - launch_arguments - + [ - set_container_executable, - set_container_mt_executable, - ] - + [OpaqueFunction(function=launch_setup)] - ) diff --git a/control_launch/launch/control.launch.xml b/control_launch/launch/control.launch.xml deleted file mode 100644 index f5d6696cc4..0000000000 --- a/control_launch/launch/control.launch.xml +++ /dev/null @@ -1,23 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - diff --git a/control_launch/package.xml b/control_launch/package.xml deleted file mode 100644 index ebf76a49f8..0000000000 --- a/control_launch/package.xml +++ /dev/null @@ -1,26 +0,0 @@ - - - - control_launch - 0.1.0 - The control_launch package - - Takamasa Horibe - - Apache License 2.0 - - ament_cmake_auto - - external_cmd_converter - lane_departure_checker - shift_decider - trajectory_follower_node - vehicle_cmd_gate - - ament_lint_auto - autoware_lint_common - - - ament_cmake - -