Skip to content

Commit

Permalink
remove on/off option for shift decider, vehicle cmd gate, and operati…
Browse files Browse the repository at this point in the history
…on mode transition manager
  • Loading branch information
xtk8532704 committed Nov 18, 2024
1 parent 6cb9e86 commit aae88c0
Showing 1 changed file with 74 additions and 93 deletions.
167 changes: 74 additions & 93 deletions launch/tier4_control_launch/launch/control.launch.xml
Original file line number Diff line number Diff line change
@@ -1,15 +1,11 @@
<launch>

<!-- controler -->

Check warning on line 2 in launch/tier4_control_launch/launch/control.launch.xml

View workflow job for this annotation

GitHub Actions / spell-check-differential

Unknown word (controler)
<arg name="trajectory_follower_mode" default="trajectory_follower_node"/>
<arg name="lateral_controller_mode"/>
<arg name="longitudinal_controller_mode"/>
<arg name="check_external_emergency_heartbeat"/>
<arg name="use_aeb_autoware_state_check"/>

<!-- control-related modules, turn off only when debugging/testing. -->
<arg name="launch_shift_decider" default="true"/>
<arg name="launch_vehicle_cmd_gate" default="true"/>
<arg name="launch_operation_mode_transition_manager" default="true"/>
<!-- external cmd selector and converter -->
<arg name="launch_external_cmd_selector" default="true"/>
<arg name="launch_external_cmd_converter" default="true"/>

Expand All @@ -21,6 +17,7 @@
<arg name="launch_obstacle_collision_checker" default="false"/>
<arg name="launch_predicted_path_checker" default="false"/>
<arg name="launch_control_evaluator" default="true"/>
<arg name="use_aeb_autoware_state_check"/>

<!-- common param path -->
<arg name="vehicle_param_file"/>
Expand Down Expand Up @@ -55,6 +52,77 @@
<!-- set a control container to run all required components in the same process -->
<node_container pkg="rclcpp_components" exec="$(var container_executable)" name="control_container" namespace="">
<composable_node pkg="glog_component" plugin="GlogComponent" name="glog_control_container_component"/>
<!-- shift decider -->
<composable_node pkg="autoware_shift_decider" plugin="autoware::shift_decider::ShiftDecider" name="autoware_shift_decider">
<remap from="input/control_cmd" to="/control/trajectory_follower/control_cmd"/>
<remap from="input/state" to="/autoware/state"/>
<remap from="input/current_gear" to="/vehicle/status/gear_status"/>
<remap from="output/gear_cmd" to="/control/shift_decider/gear_cmd"/>
<param from="$(var shift_decider_param_path)"/>
<extra_arg name="use_intra_process_comms" value="$(var use_intra_process)"/>
</composable_node>
<!-- vehicle cmd gate -->
<composable_node pkg="autoware_vehicle_cmd_gate" plugin="autoware::vehicle_cmd_gate::VehicleCmdGate" name="vehicle_cmd_gate">
<remap from="input/steering" to="/vehicle/status/steering_status"/>
<remap from="input/operation_mode" to="/system/operation_mode/state"/>
<remap from="input/auto/control_cmd" to="/control/trajectory_follower/control_cmd"/>
<remap from="input/auto/turn_indicators_cmd" to="/planning/turn_indicators_cmd"/>
<remap from="input/auto/hazard_lights_cmd" to="/planning/hazard_lights_cmd"/>
<remap from="input/auto/gear_cmd" to="/control/shift_decider/gear_cmd"/>
<remap from="input/external/control_cmd" to="/external/selected/control_cmd"/>
<remap from="input/external/turn_indicators_cmd" to="/external/selected/turn_indicators_cmd"/>
<remap from="input/external/hazard_lights_cmd" to="/external/selected/hazard_lights_cmd"/>
<remap from="input/external/gear_cmd" to="/external/selected/gear_cmd"/>
<remap from="input/external_emergency_stop_heartbeat" to="/external/selected/heartbeat"/>
<remap from="input/gate_mode" to="/control/gate_mode_cmd"/>
<remap from="input/emergency/control_cmd" to="/system/emergency/control_cmd"/>
<remap from="input/emergency/hazard_lights_cmd" to="/system/emergency/hazard_lights_cmd"/>
<remap from="input/emergency/gear_cmd" to="/system/emergency/gear_cmd"/>
<remap from="input/mrm_state" to="/system/fail_safe/mrm_state"/>
<remap from="input/kinematics" to="/localization/kinematic_state"/>
<remap from="input/acceleration" to="/localization/acceleration"/>
<remap from="output/vehicle_cmd_emergency" to="/control/command/emergency_cmd"/>
<remap from="output/control_cmd" to="/control/command/control_cmd"/>
<remap from="output/gear_cmd" to="/control/command/gear_cmd"/>
<remap from="output/turn_indicators_cmd" to="/control/command/turn_indicators_cmd"/>
<remap from="output/hazard_lights_cmd" to="/control/command/hazard_lights_cmd"/>
<remap from="output/gate_mode" to="/control/current_gate_mode"/>
<remap from="output/engage" to="/api/autoware/get/engage"/>
<remap from="output/external_emergency" to="/api/autoware/get/emergency"/>
<remap from="output/operation_mode" to="/control/vehicle_cmd_gate/operation_mode"/>
<remap from="~/service/engage" to="/api/autoware/set/engage"/>
<remap from="~/service/external_emergency" to="/api/autoware/set/emergency"/>
<!-- TODO(Takagi, Isamu): deprecated -->
<remap from="input/engage" to="/autoware/engage"/>
<remap from="~/service/external_emergency_stop" to="~/external_emergency_stop"/>
<remap from="~/service/clear_external_emergency_stop" to="~/clear_external_emergency_stop"/>
<param from="$(var vehicle_cmd_gate_param_path)"/>
<param from="$(var vehicle_param_file)"/>
<param name="check_external_emergency_heartbeat" value="$(var check_external_emergency_heartbeat)"/>
<extra_arg name="use_intra_process_comms" value="$(var use_intra_process)"/>
</composable_node>
<!-- operation mode transition manager -->
<composable_node
pkg="autoware_operation_mode_transition_manager"
plugin="autoware::operation_mode_transition_manager::OperationModeTransitionManager"
name="autoware_operation_mode_transition_manager"
>
<!-- input -->
<remap from="kinematics" to="/localization/kinematic_state"/>
<remap from="steering" to="/vehicle/status/steering_status"/>
<remap from="trajectory" to="/planning/scenario_planning/trajectory"/>
<remap from="control_cmd" to="/control/command/control_cmd"/>
<remap from="trajectory_follower_control_cmd" to="/control/trajectory_follower/control_cmd"/>
<remap from="control_mode_report" to="/vehicle/status/control_mode"/>
<remap from="gate_operation_mode" to="/control/vehicle_cmd_gate/operation_mode"/>
<!-- output -->
<remap from="is_autonomous_available" to="/control/is_autonomous_available"/>
<remap from="control_mode_request" to="/control/control_mode_request"/>
<param from="$(var nearest_search_param_path)"/>
<param from="$(var operation_mode_transition_manager_param_path)"/>
<param from="$(var vehicle_param_file)"/>
<extra_arg name="use_intra_process_comms" value="$(var use_intra_process)"/>
</composable_node>
</node_container>

<!-- trajectory_follower_node -->
Expand Down Expand Up @@ -89,92 +157,6 @@
<node pkg="autoware_smart_mpc_trajectory_follower" exec="pympc_trajectory_follower.py" name="controller_node_exe"/>
</group>

<!-- shift decider -->
<group if="$(var launch_shift_decider)">
<load_composable_node target="/control/control_container">
<composable_node pkg="autoware_shift_decider" plugin="autoware::shift_decider::ShiftDecider" name="autoware_shift_decider">
<remap from="input/control_cmd" to="/control/trajectory_follower/control_cmd"/>
<remap from="input/state" to="/autoware/state"/>
<remap from="input/current_gear" to="/vehicle/status/gear_status"/>
<remap from="output/gear_cmd" to="/control/shift_decider/gear_cmd"/>
<param from="$(var shift_decider_param_path)"/>
<extra_arg name="use_intra_process_comms" value="$(var use_intra_process)"/>
</composable_node>
</load_composable_node>
</group>

<!-- vehicle cmd gate -->
<group if="$(var launch_vehicle_cmd_gate)">
<load_composable_node target="/control/control_container">
<composable_node pkg="autoware_vehicle_cmd_gate" plugin="autoware::vehicle_cmd_gate::VehicleCmdGate" name="vehicle_cmd_gate">
<remap from="input/steering" to="/vehicle/status/steering_status"/>
<remap from="input/operation_mode" to="/system/operation_mode/state"/>
<remap from="input/auto/control_cmd" to="/control/trajectory_follower/control_cmd"/>
<remap from="input/auto/turn_indicators_cmd" to="/planning/turn_indicators_cmd"/>
<remap from="input/auto/hazard_lights_cmd" to="/planning/hazard_lights_cmd"/>
<remap from="input/auto/gear_cmd" to="/control/shift_decider/gear_cmd"/>
<remap from="input/external/control_cmd" to="/external/selected/control_cmd"/>
<remap from="input/external/turn_indicators_cmd" to="/external/selected/turn_indicators_cmd"/>
<remap from="input/external/hazard_lights_cmd" to="/external/selected/hazard_lights_cmd"/>
<remap from="input/external/gear_cmd" to="/external/selected/gear_cmd"/>
<remap from="input/external_emergency_stop_heartbeat" to="/external/selected/heartbeat"/>
<remap from="input/gate_mode" to="/control/gate_mode_cmd"/>
<remap from="input/emergency/control_cmd" to="/system/emergency/control_cmd"/>
<remap from="input/emergency/hazard_lights_cmd" to="/system/emergency/hazard_lights_cmd"/>
<remap from="input/emergency/gear_cmd" to="/system/emergency/gear_cmd"/>
<remap from="input/mrm_state" to="/system/fail_safe/mrm_state"/>
<remap from="input/kinematics" to="/localization/kinematic_state"/>
<remap from="input/acceleration" to="/localization/acceleration"/>
<remap from="output/vehicle_cmd_emergency" to="/control/command/emergency_cmd"/>
<remap from="output/control_cmd" to="/control/command/control_cmd"/>
<remap from="output/gear_cmd" to="/control/command/gear_cmd"/>
<remap from="output/turn_indicators_cmd" to="/control/command/turn_indicators_cmd"/>
<remap from="output/hazard_lights_cmd" to="/control/command/hazard_lights_cmd"/>
<remap from="output/gate_mode" to="/control/current_gate_mode"/>
<remap from="output/engage" to="/api/autoware/get/engage"/>
<remap from="output/external_emergency" to="/api/autoware/get/emergency"/>
<remap from="output/operation_mode" to="/control/vehicle_cmd_gate/operation_mode"/>
<remap from="~/service/engage" to="/api/autoware/set/engage"/>
<remap from="~/service/external_emergency" to="/api/autoware/set/emergency"/>
<!-- TODO(Takagi, Isamu): deprecated -->
<remap from="input/engage" to="/autoware/engage"/>
<remap from="~/service/external_emergency_stop" to="~/external_emergency_stop"/>
<remap from="~/service/clear_external_emergency_stop" to="~/clear_external_emergency_stop"/>
<param from="$(var vehicle_cmd_gate_param_path)"/>
<param from="$(var vehicle_param_file)"/>
<param name="check_external_emergency_heartbeat" value="$(var check_external_emergency_heartbeat)"/>
<extra_arg name="use_intra_process_comms" value="$(var use_intra_process)"/>
</composable_node>
</load_composable_node>
</group>

<!-- operation mode transition manager -->
<group if="$(var launch_operation_mode_transition_manager)">
<load_composable_node target="/control/control_container">
<composable_node
pkg="autoware_operation_mode_transition_manager"
plugin="autoware::operation_mode_transition_manager::OperationModeTransitionManager"
name="autoware_operation_mode_transition_manager"
>
<!-- input -->
<remap from="kinematics" to="/localization/kinematic_state"/>
<remap from="steering" to="/vehicle/status/steering_status"/>
<remap from="trajectory" to="/planning/scenario_planning/trajectory"/>
<remap from="control_cmd" to="/control/command/control_cmd"/>
<remap from="trajectory_follower_control_cmd" to="/control/trajectory_follower/control_cmd"/>
<remap from="control_mode_report" to="/vehicle/status/control_mode"/>
<remap from="gate_operation_mode" to="/control/vehicle_cmd_gate/operation_mode"/>
<!-- output -->
<remap from="is_autonomous_available" to="/control/is_autonomous_available"/>
<remap from="control_mode_request" to="/control/control_mode_request"/>
<param from="$(var nearest_search_param_path)"/>
<param from="$(var operation_mode_transition_manager_param_path)"/>
<param from="$(var vehicle_param_file)"/>
<extra_arg name="use_intra_process_comms" value="$(var use_intra_process)"/>
</composable_node>
</load_composable_node>
</group>

<!-- external cmd selector -->
<group if="$(var launch_external_cmd_selector)">
<include file="$(find-pkg-share autoware_external_cmd_selector)/launch/external_cmd_selector.launch.py">
Expand All @@ -183,7 +165,6 @@
<arg name="external_cmd_selector_param_path" value="$(var external_cmd_selector_param_path)"/>
</include>
</group>

<!-- external cmd converter -->
<group if="$(var launch_external_cmd_converter)">
<include file="$(find-pkg-share autoware_external_cmd_converter)/launch/external_cmd_converter.launch.py">
Expand Down

0 comments on commit aae88c0

Please sign in to comment.