Skip to content

Commit

Permalink
fix: add pure_pursuit as lateral controller into launch files (autowa…
Browse files Browse the repository at this point in the history
…refoundation#750)

Signed-off-by: Berkay <[email protected]>
  • Loading branch information
brkay54 authored Apr 22, 2022
1 parent 32502db commit 5653ae4
Show file tree
Hide file tree
Showing 2 changed files with 48 additions and 11 deletions.
1 change: 1 addition & 0 deletions control/pure_pursuit/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -56,4 +56,5 @@ endif()

ament_auto_package(INSTALL_TO_SHARE
launch
config
)
58 changes: 47 additions & 11 deletions launch/tier4_control_launch/launch/control.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,7 @@


def launch_setup(context, *args, **kwargs):
lateral_controller_mode = LaunchConfiguration("lateral_controller_mode").perform(context)
vehicle_info_param_path = LaunchConfiguration("vehicle_info_param_file").perform(context)
with open(vehicle_info_param_path, "r") as f:
vehicle_info_param = yaml.safe_load(f)["/**"]["ros__parameters"]
Expand All @@ -43,7 +44,9 @@ def launch_setup(context, *args, **kwargs):
latlon_muxer_param_path = LaunchConfiguration("latlon_muxer_param_path").perform(context)
with open(latlon_muxer_param_path, "r") as f:
latlon_muxer_param = yaml.safe_load(f)["/**"]["ros__parameters"]

pure_pursuit_param_path = LaunchConfiguration("pure_pursuit_param_path").perform(context)
with open(pure_pursuit_param_path, "r") as f:
pure_pursuit_param = yaml.safe_load(f)["/**"]["ros__parameters"]
vehicle_cmd_gate_param_path = LaunchConfiguration("vehicle_cmd_gate_param_path").perform(
context
)
Expand Down Expand Up @@ -76,6 +79,22 @@ def launch_setup(context, *args, **kwargs):
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
)

pure_pursuit_component = ComposableNode(
package="pure_pursuit",
plugin="pure_pursuit::PurePursuitNode",
name="pure_pursuit_node_exe",
namespace="trajectory_follower",
remappings=[
("input/reference_trajectory", "/planning/scenario_planning/trajectory"),
("input/current_odometry", "/localization/kinematic_state"),
("output/control_raw", "lateral/control_cmd"),
],
parameters=[
pure_pursuit_param,
],
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
)

# longitudinal controller
lon_controller_component = ComposableNode(
package="trajectory_follower_nodes",
Expand Down Expand Up @@ -238,11 +257,18 @@ def launch_setup(context, *args, **kwargs):
)

# lateral controller is separated since it may be another controller (e.g. pure pursuit)
lat_controller_loader = LoadComposableNodes(
composable_node_descriptions=[lat_controller_component],
target_container=container,
# condition=LaunchConfigurationEquals("lateral_controller_mode", "mpc"),
)
if lateral_controller_mode == "mpc_follower":
lat_controller_loader = LoadComposableNodes(
composable_node_descriptions=[lat_controller_component],
target_container=container,
# condition=LaunchConfigurationEquals("lateral_controller_mode", "mpc"),
)
elif lateral_controller_mode == "pure_pursuit":
lat_controller_loader = LoadComposableNodes(
composable_node_descriptions=[pure_pursuit_component],
target_container=container,
# condition=LaunchConfigurationEquals("lateral_controller_mode", "mpc"),
)

group = GroupAction(
[
Expand All @@ -265,11 +291,13 @@ def add_launch_arg(name: str, default_value=None, description=None):
DeclareLaunchArgument(name, default_value=default_value, description=description)
)

# add_launch_arg(
# "lateral_controller_mode",
# "mpc_follower",
# "lateral controller mode: `mpc_follower` or `pure_pursuit`",
# )
# lateral controller

add_launch_arg(
"lateral_controller_mode",
"mpc_follower",
"lateral controller mode: `mpc_follower` or `pure_pursuit`",
)

add_launch_arg(
"vehicle_info_param_file",
Expand All @@ -288,6 +316,14 @@ def add_launch_arg(name: str, default_value=None, description=None):
],
"path to the parameter file of lateral controller",
)
add_launch_arg(
"pure_pursuit_param_path",
[
FindPackageShare("pure_pursuit"),
"/config/pure_pursuit.param.yaml",
],
"path to the parameter file of lateral controller",
)
add_launch_arg(
"lon_controller_param_path",
[
Expand Down

0 comments on commit 5653ae4

Please sign in to comment.