Skip to content

Commit

Permalink
Added pkg to control.launch.py
Browse files Browse the repository at this point in the history
Signed-off-by: Berkay Karaman <[email protected]>
  • Loading branch information
brkay54 committed Sep 28, 2023
1 parent 4ffe0ea commit 1f2f0aa
Showing 1 changed file with 32 additions and 0 deletions.
32 changes: 32 additions & 0 deletions launch/tier4_control_launch/launch/control.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -63,6 +63,8 @@ def launch_setup(context, *args, **kwargs):
obstacle_collision_checker_param = yaml.safe_load(f)["/**"]["ros__parameters"]
with open(LaunchConfiguration("aeb_param_path").perform(context), "r") as f:
aeb_param = yaml.safe_load(f)["/**"]["ros__parameters"]
with open(LaunchConfiguration("predicted_path_checker_param_path").perform(context), "r") as f:
predicted_path_checker_param = yaml.safe_load(f)["/**"]["ros__parameters"]

controller_component = ComposableNode(
package="trajectory_follower_node",
Expand Down Expand Up @@ -176,6 +178,34 @@ def launch_setup(context, *args, **kwargs):
target_container="/control/control_container",
)

# autonomous emergency braking
predicted_path_checker = ComposableNode(
package="predicted_path_checker",
plugin="autoware::motion::control::predicted_path_checker::PredictedPathCheckerNode",
name="predicted_path_checker",
remappings=[
("~/input/objects", "/perception/object_recognition/objects"),
("~/input/reference_trajectory", "/planning/scenario_planning/trajectory"),
("~/input/current_accel", "/localization/acceleration"),
("~/input/odometry", "/localization/kinematic_state"),
(
"~/input/predicted_trajectory",
"/control/trajectory_follower/lateral/predicted_trajectory",
),
],
parameters=[
vehicle_info_param,
predicted_path_checker_param,
],
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
)

predicted_path_checker_loader = LoadComposableNodes(
condition=IfCondition(LaunchConfiguration("enable_predicted_path_checker")),
composable_node_descriptions=[predicted_path_checker],
target_container="/control/control_container",
)

# vehicle cmd gate
vehicle_cmd_gate_component = ComposableNode(
package="vehicle_cmd_gate",
Expand Down Expand Up @@ -338,6 +368,7 @@ def launch_setup(context, *args, **kwargs):
external_cmd_converter_loader,
obstacle_collision_checker_loader,
autonomous_emergency_braking_loader,
predicted_path_checker_loader,

Check warning on line 371 in launch/tier4_control_launch/launch/control.launch.py

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Large Method

launch_setup increases from 282 to 310 lines of code, threshold = 70. Large functions with many lines of code are generally harder to understand and lower the code health. Avoid adding more lines to this function.
]
)

Expand Down Expand Up @@ -372,6 +403,7 @@ def add_launch_arg(name: str, default_value=None, description=None):
add_launch_arg("obstacle_collision_checker_param_path")
add_launch_arg("external_cmd_selector_param_path")
add_launch_arg("aeb_param_path")
add_launch_arg("predicted_path_checker_param_path")
add_launch_arg("enable_autonomous_emergency_braking")
add_launch_arg("check_external_emergency_heartbeat")

Expand Down

0 comments on commit 1f2f0aa

Please sign in to comment.