|
| 1 | +<?xml version="1.0" encoding="UTF-8"?> |
| 2 | +<launch> |
| 3 | + <!-- Essential parameters --> |
| 4 | + <arg name="vehicle_model" default="sample_vehicle" description="vehicle model name"/> |
| 5 | + <arg name="sensor_model" default="sample_sensor_kit" description="sensor model name"/> |
| 6 | + <arg name="data_path" default="$(env HOME)/autoware_data" description="packages data and artifacts directory path"/> |
| 7 | + |
| 8 | + <!-- launch module preset --> |
| 9 | + <arg name="planning_module_preset" default="x2" description="planning module preset"/> |
| 10 | + <arg name="control_module_preset" default="x2" description="control module preset"/> |
| 11 | + |
| 12 | + <!-- Optional parameters --> |
| 13 | + <!-- Modules to be launched --> |
| 14 | + <arg name="launch_vehicle" default="true" description="launch vehicle"/> |
| 15 | + <arg name="launch_system" default="true" description="launch system"/> |
| 16 | + <arg name="launch_map" default="true" description="launch map"/> |
| 17 | + <arg name="launch_sensing" default="true" description="launch sensing"/> |
| 18 | + <arg name="launch_sensing_driver" default="true" description="launch sensing driver"/> |
| 19 | + <arg name="launch_localization" default="true" description="launch localization"/> |
| 20 | + <arg name="launch_perception" default="true" description="launch perception"/> |
| 21 | + <arg name="launch_planning" default="true" description="launch planning"/> |
| 22 | + <arg name="launch_control" default="true" description="launch control"/> |
| 23 | + <arg name="launch_api" default="true" description="launch api"/> |
| 24 | + <arg name="launch_v2x" default="true" description="launch V2X"/> |
| 25 | + <arg name="launch_l4_toolkit" default="true" description="launch L4 Toolkit"/> |
| 26 | + <!-- Global parameters --> |
| 27 | + <arg name="use_sim_time" default="false" description="use_sim_time"/> |
| 28 | + <arg name="is_main_ecu" default="false"/> |
| 29 | + <arg name="is_redundant" default="true"/> |
| 30 | + <!-- Vehicle --> |
| 31 | + <arg name="vehicle_id" default="$(env VEHICLE_ID default)" description="vehicle specific ID"/> |
| 32 | + |
| 33 | + <!-- Global parameters --> |
| 34 | + <group scoped="false"> |
| 35 | + <include file="$(find-pkg-share autoware_global_parameter_loader)/launch/global_params.launch.py"> |
| 36 | + <arg name="use_sim_time" value="$(var use_sim_time)"/> |
| 37 | + <arg name="vehicle_model" value="$(var vehicle_model)"/> |
| 38 | + </include> |
| 39 | + </group> |
| 40 | + |
| 41 | + <!-- Planning --> |
| 42 | + <group if="$(var launch_planning)"> |
| 43 | + <!--- preset --> |
| 44 | + <include file="$(find-pkg-share autoware_launch)/config/planning/preset/$(var planning_module_preset)_preset.yaml"/> |
| 45 | + |
| 46 | + <!-- Planning args --> |
| 47 | + <arg name="common_config_path" default="$(find-pkg-share autoware_launch)/config/planning/scenario_planning/common"/> |
| 48 | + <arg name="common_param_path" default="$(var common_config_path)/common.param.yaml"/> |
| 49 | + <arg name="nearest_search_param_path" default="$(var common_config_path)/nearest_search.param.yaml"/> |
| 50 | + <arg name="velocity_smoother_param_path" default="$(var common_config_path)/autoware_velocity_smoother/velocity_smoother.param.yaml"/> |
| 51 | + <arg name="velocity_smoother_type_param_path" default="$(var common_config_path)/autoware_velocity_smoother/$(var velocity_smoother_type).param.yaml"/> |
| 52 | + |
| 53 | + <!-- topic relay controller --> |
| 54 | + <include file="$(find-pkg-share autoware_topic_relay_controller)/launch/topic_relay_controller.launch.xml"> |
| 55 | + <arg name="node_name_suffix" value="trajectory"/> |
| 56 | + <arg name="config_file" value="$(find-pkg-share autoware_launch)/config/system/topic_relay_controller/main_planning_scenario_planning_trajectory.param.yaml"/> |
| 57 | + </include> |
| 58 | + |
| 59 | + <!-- external velocity limit selector --> |
| 60 | + <group> |
| 61 | + <include file="$(find-pkg-share autoware_external_velocity_limit_selector)/launch/external_velocity_limit_selector.launch.xml"> |
| 62 | + <arg name="common_param_path" value="$(var common_param_path)"/> |
| 63 | + <arg name="param_path" value="$(var velocity_smoother_param_path)"/> |
| 64 | + </include> |
| 65 | + </group> |
| 66 | + |
| 67 | + <!-- motion velocity smoother --> |
| 68 | + <group> |
| 69 | + <node_container pkg="rclcpp_components" exec="component_container" name="velocity_smoother_container" namespace=""> |
| 70 | + <composable_node pkg="autoware_velocity_smoother" plugin="autoware::velocity_smoother::VelocitySmootherNode" name="velocity_smoother" namespace=""> |
| 71 | + <param name="algorithm_type" value="$(var velocity_smoother_type)"/> |
| 72 | + <param from="$(var common_param_path)"/> |
| 73 | + <param from="$(var nearest_search_param_path)"/> |
| 74 | + <param from="$(var velocity_smoother_param_path)"/> |
| 75 | + <param from="$(var velocity_smoother_type_param_path)"/> |
| 76 | + |
| 77 | + <param name="publish_debug_trajs" value="true"/> |
| 78 | + <remap from="~/input/trajectory" to="/planning/topic_relay_controller/trajectory"/> |
| 79 | + <remap from="~/output/trajectory" to="/planning/scenario_planning/trajectory"/> |
| 80 | + |
| 81 | + <remap from="~/input/external_velocity_limit_mps" to="/planning/scenario_planning/max_velocity"/> |
| 82 | + <remap from="~/input/acceleration" to="/localization/acceleration"/> |
| 83 | + <remap from="/localization/kinematic_state" to="/localization/kinematic_state"/> |
| 84 | + <remap from="~/input/operation_mode_state" to="/system/operation_mode/state"/> |
| 85 | + <remap from="~/output/current_velocity_limit_mps" to="/planning/scenario_planning/current_max_velocity"/> |
| 86 | + </composable_node> |
| 87 | + <composable_node pkg="glog_component" plugin="GlogComponent" name="glog_component" namespace=""/> |
| 88 | + </node_container> |
| 89 | + </group> |
| 90 | + </group> |
| 91 | + |
| 92 | + <!-- Control --> |
| 93 | + <group if="$(var launch_control)"> |
| 94 | + <!-- Control args --> |
| 95 | + <arg name="lateral_controller_mode" default="mpc"/> |
| 96 | + <arg name="longitudinal_controller_mode" default="pid"/> |
| 97 | + <arg name="use_individual_control_param" default="false"/> |
| 98 | + <let name="latlon_controller_param_path_dir" value="$(var vehicle_id)" if="$(var use_individual_control_param)"/> |
| 99 | + <let name="latlon_controller_param_path_dir" value="" unless="$(var use_individual_control_param)"/> |
| 100 | + |
| 101 | + <arg name="nearest_search_param_path" default="$(find-pkg-share autoware_launch)/config/control/common/nearest_search.param.yaml"/> |
| 102 | + <arg name="trajectory_follower_node_param_path" default="$(find-pkg-share autoware_launch)/config/control/trajectory_follower/trajectory_follower_node.param.yaml"/> |
| 103 | + <arg |
| 104 | + name="lat_controller_param_path" |
| 105 | + default="$(find-pkg-share autoware_launch)/config/control/trajectory_follower/$(var latlon_controller_param_path_dir)/lateral/$(var lateral_controller_mode).param.yaml" |
| 106 | + /> |
| 107 | + <arg |
| 108 | + name="lon_controller_param_path" |
| 109 | + default="$(find-pkg-share autoware_launch)/config/control/trajectory_follower/$(var latlon_controller_param_path_dir)/longitudinal/$(var longitudinal_controller_mode).redundancy.sub.param.yaml" |
| 110 | + /> |
| 111 | + <arg name="vehicle_info_param_path" default="$(find-pkg-share $(var vehicle_model)_description)/config/vehicle_info.param.yaml"/> |
| 112 | + |
| 113 | + <!-- trajectory follower --> |
| 114 | + <node_container pkg="rclcpp_components" exec="component_container" name="trajectory_follower_container" namespace=""> |
| 115 | + <composable_node pkg="autoware_trajectory_follower_node" plugin="autoware::motion::control::trajectory_follower_node::Controller" name="trajectory_follower_node_exe" namespace=""> |
| 116 | + <param name="lateral_controller_mode" value="$(var lateral_controller_mode)"/> |
| 117 | + <param name="longitudinal_controller_mode" value="$(var longitudinal_controller_mode)"/> |
| 118 | + <param from="$(var nearest_search_param_path)"/> |
| 119 | + <param from="$(var trajectory_follower_node_param_path)"/> |
| 120 | + <param from="$(var lon_controller_param_path)"/> |
| 121 | + <param from="$(var lat_controller_param_path)"/> |
| 122 | + <param from="$(var vehicle_info_param_path)"/> |
| 123 | + |
| 124 | + <remap from="~/input/reference_trajectory" to="/planning/scenario_planning/trajectory"/> |
| 125 | + <remap from="~/input/current_steering" to="/vehicle/status/steering_status"/> |
| 126 | + <remap from="~/input/current_odometry" to="/localization/kinematic_state"/> |
| 127 | + <remap from="~/input/current_accel" to="/localization/acceleration"/> |
| 128 | + <remap from="~/input/current_operation_mode" to="/system/operation_mode/state"/> |
| 129 | + <remap from="~/output/control_cmd" to="/control/command/control_cmd"/> |
| 130 | + </composable_node> |
| 131 | + <composable_node pkg="glog_component" plugin="GlogComponent" name="glog_component" namespace=""/> |
| 132 | + </node_container> |
| 133 | + </group> |
| 134 | + |
| 135 | + <!-- System --> |
| 136 | + <group if="$(var launch_system)"> |
| 137 | + <!-- System args --> |
| 138 | + <arg name="domain_bridge_param_path" default="$(find-pkg-share autoware_launch)/config/system/domain_bridge/domain_bridge.redundancy.sub.psim.param.yaml"/> |
| 139 | + <arg name="mrm_stop_operator_param_path" default="$(find-pkg-share mrm_stop_operator)/config/mrm_stop_operator.param.yaml"/> |
| 140 | + |
| 141 | + <!-- domain bridge --> |
| 142 | + <include file="$(find-pkg-share domain_bridge)/launch/domain_bridge.launch.xml"> |
| 143 | + <arg name="config" value="$(var domain_bridge_param_path)"/> |
| 144 | + <!-- Optionally override domain IDs --> |
| 145 | + <arg name="from_domain" value="1"/> |
| 146 | + <arg name="to_domain" value="2"/> |
| 147 | + </include> |
| 148 | + |
| 149 | + <!-- diagnostic_graph_aggregator --> |
| 150 | + <include file="$(find-pkg-share autoware_system_diagnostic_monitor)/launch/system_diagnostic_monitor.launch.xml"> |
| 151 | + <arg name="param_file" value="$(find-pkg-share autoware_diagnostic_graph_aggregator)/config/default.param.yaml"/> |
| 152 | + <arg name="graph_file" value="$(find-pkg-share autoware_launch)/config/system/tier4_diagnostics/autoware-main.redundancy.sub.yaml"/> |
| 153 | + </include> |
| 154 | + |
| 155 | + <!-- topic_state_monitor --> |
| 156 | + <include file="$(find-pkg-share autoware_topic_state_monitor)/launch/topic_state_monitor.launch.xml"> |
| 157 | + <arg name="node_name_suffix" value="stop_filter"/> |
| 158 | + <arg name="topic" value="/localization/kinematic_state"/> |
| 159 | + <arg name="topic_type" value="nav_msgs/msg/Odometry"/> |
| 160 | + <arg name="diag_name" value="planning_topic_status"/> |
| 161 | + <arg name="warn_rate" value="20.0"/> |
| 162 | + <arg name="error_rate" value="4.0"/> |
| 163 | + <arg name="timeout" value="0.25"/> |
| 164 | + </include> |
| 165 | + |
| 166 | + <include file="$(find-pkg-share autoware_topic_state_monitor)/launch/topic_state_monitor.launch.xml"> |
| 167 | + <arg name="node_name_suffix" value="twist2accel"/> |
| 168 | + <arg name="topic" value="/localization/acceleration"/> |
| 169 | + <arg name="topic_type" value="geometry_msgs/msg/AccelWithCovarianceStamped"/> |
| 170 | + <arg name="diag_name" value="planning_topic_status"/> |
| 171 | + <arg name="warn_rate" value="20.0"/> |
| 172 | + <arg name="error_rate" value="4.0"/> |
| 173 | + <arg name="timeout" value="0.25"/> |
| 174 | + </include> |
| 175 | + |
| 176 | + <include file="$(find-pkg-share autoware_topic_state_monitor)/launch/topic_state_monitor.launch.xml"> |
| 177 | + <arg name="node_name_suffix" value="trajectory_follower"/> |
| 178 | + <arg name="topic" value="/control/command/control_cmd"/> |
| 179 | + <arg name="topic_type" value="autoware_control_msgs/msg/Control"/> |
| 180 | + <arg name="diag_name" value="control_topic_status"/> |
| 181 | + <arg name="warn_rate" value="15.0"/> |
| 182 | + <arg name="error_rate" value="3.0"/> |
| 183 | + <arg name="timeout" value="0.3"/> |
| 184 | + </include> |
| 185 | + |
| 186 | + <!-- redundancy_switcher_interface --> |
| 187 | + <include file="$(find-pkg-share redundancy_switcher_interface)/launch/redundancy_switcher_interface.launch.xml"> |
| 188 | + <arg name="param_file" value="$(find-pkg-share redundancy_switcher_interface)/config/redundancy_switcher_interface.param.yaml"/> |
| 189 | + </include> |
| 190 | + |
| 191 | + <!-- mrm stop operator --> |
| 192 | + <include file="$(find-pkg-share mrm_stop_operator)/launch/mrm_stop_operator.launch.xml"> |
| 193 | + <arg name="mrm_stop_operator_param_path" value="$(var mrm_stop_operator_param_path)"/> |
| 194 | + </include> |
| 195 | + |
| 196 | + <!-- dummy operation mode publisher --> |
| 197 | + <include file="$(find-pkg-share dummy_operation_mode_publisher)/launch/dummy_operation_mode_publisher.launch.xml"/> |
| 198 | + </group> |
| 199 | +</launch> |
0 commit comments