Skip to content

Commit

Permalink
feat(shift_decider): add shift decider config (#484)
Browse files Browse the repository at this point in the history
Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com>

Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com>
  • Loading branch information
TakaHoribe authored Sep 14, 2022
1 parent 5b3d44f commit de49ece
Show file tree
Hide file tree
Showing 3 changed files with 18 additions and 3 deletions.
3 changes: 3 additions & 0 deletions control_launch/config/shift_decider/shift_decider.param.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
/**:
ros__parameters:
park_on_goal: true
16 changes: 13 additions & 3 deletions control_launch/launch/control.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -56,6 +56,10 @@ def launch_setup(context, *args, **kwargs):
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_nodes",
plugin="autoware::motion::control::trajectory_follower_nodes::Controller",
Expand Down Expand Up @@ -114,9 +118,7 @@ def launch_setup(context, *args, **kwargs):
("output/gear_cmd", "/control/shift_decider/gear_cmd"),
],
parameters=[
{
"park_on_goal": True,
}
shift_decider_param,
],
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
)
Expand Down Expand Up @@ -304,6 +306,14 @@ def add_launch_arg(name: str, default_value=None, description=None):
],
"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.param.yaml",
],
"path to the parameter file of shift_decider",
)

# vehicle cmd gate
add_launch_arg("use_emergency_handling", "false", "use emergency handling")
Expand Down
2 changes: 2 additions & 0 deletions control_launch/launch/control.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
<arg name="latlon_muxer_param_path" default="$(find-pkg-share control_launch)/config/trajectory_follower/latlon_muxer.param.yaml"/>
<arg name="vehicle_cmd_gate_param_path" default="$(find-pkg-share control_launch)/config/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml"/>
<arg name="operation_mode_transition_manager_param_path" default="$(find-pkg-share control_launch)/config/operation_mode_transition_manager/operation_mode_transition_manager.param.yaml"/>
<arg name="shift_decider_param_path" default="$(find-pkg-share control_launch)/config/shift_decider/shift_decider.param.yaml"/>

<include file="$(find-pkg-share control_launch)/launch/control.launch.py">
<arg name="lateral_controller_mode" value="$(var lateral_controller_mode)" />
Expand All @@ -14,6 +15,7 @@
<arg name="latlon_muxer_param_path" value="$(var latlon_muxer_param_path)"/>
<arg name="vehicle_cmd_gate_param_path" value="$(var vehicle_cmd_gate_param_path)"/>
<arg name="operation_mode_transition_manager_param_path" value="$(var operation_mode_transition_manager_param_path)"/>
<arg name="shift_decider_param_path" value="$(var shift_decider_param_path)"/>
</include>

</launch>

0 comments on commit de49ece

Please sign in to comment.