From f1d4bd97515262c5bdc529c3d692bfcd7882fe61 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 22 Mar 2022 12:45:45 +0900 Subject: [PATCH 1/2] add obstacle_velocity_planner Signed-off-by: Takayuki Murooka --- .../motion_planning/motion_planning.launch.py | 29 ++++++++++++++++++- 1 file changed, 28 insertions(+), 1 deletion(-) diff --git a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py index 58b685919..0785f8e72 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py +++ b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py @@ -120,6 +120,32 @@ def generate_launch_description(): extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) + # obstacle velocity planner + # TODO(murooka) use launcher param + obstacle_velocity_planner_param_path = os.path.join( + get_package_share_directory('obstacle_velocity_planner'), + 'config', + 'obstacle_velocity_planner.param.yaml', + ) + with open(obstacle_velocity_planner_param_path, 'r') as f: + obstacle_velocity_planner_param = yaml.safe_load(f)['/**']['ros__parameters'] + obstacle_velocity_planner_component = ComposableNode( + package='obstacle_velocity_planner', + plugin='ObstacleVelocityPlanner', + name='obstacle_velocity_planner', + namespace='', + remappings=[ + ("~/output/trajectory", "/planning/scenario_planning/lane_driving/trajectory"), + ('~/input/trajectory', 'surround_obstacle_checker/trajectory'), + ], + parameters=[ + obstacle_velocity_planner_param, + ], + extra_arguments=[ + {'use_intra_process_comms': LaunchConfiguration('use_intra_process')} + ], + ) + # obstacle stop planner obstacle_stop_planner_param_path = os.path.join( get_package_share_directory("planning_launch"), @@ -181,7 +207,8 @@ def generate_launch_description(): executable=LaunchConfiguration("container_executable"), composable_node_descriptions=[ obstacle_avoidance_planner_component, - obstacle_stop_planner_component, + obstacle_velocity_planner_component, + # obstacle_stop_planner_component, ], ) From 7e143bbea278921ffcb1f580c96ebadaac4c278b Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Tue, 22 Mar 2022 04:08:07 +0000 Subject: [PATCH 2/2] ci(pre-commit): autofix --- .../motion_planning/motion_planning.launch.py | 24 +++++++++---------- 1 file changed, 11 insertions(+), 13 deletions(-) diff --git a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py index 0785f8e72..128fdcbde 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py +++ b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py @@ -123,27 +123,25 @@ def generate_launch_description(): # obstacle velocity planner # TODO(murooka) use launcher param obstacle_velocity_planner_param_path = os.path.join( - get_package_share_directory('obstacle_velocity_planner'), - 'config', - 'obstacle_velocity_planner.param.yaml', + get_package_share_directory("obstacle_velocity_planner"), + "config", + "obstacle_velocity_planner.param.yaml", ) - with open(obstacle_velocity_planner_param_path, 'r') as f: - obstacle_velocity_planner_param = yaml.safe_load(f)['/**']['ros__parameters'] + with open(obstacle_velocity_planner_param_path, "r") as f: + obstacle_velocity_planner_param = yaml.safe_load(f)["/**"]["ros__parameters"] obstacle_velocity_planner_component = ComposableNode( - package='obstacle_velocity_planner', - plugin='ObstacleVelocityPlanner', - name='obstacle_velocity_planner', - namespace='', + package="obstacle_velocity_planner", + plugin="ObstacleVelocityPlanner", + name="obstacle_velocity_planner", + namespace="", remappings=[ ("~/output/trajectory", "/planning/scenario_planning/lane_driving/trajectory"), - ('~/input/trajectory', 'surround_obstacle_checker/trajectory'), + ("~/input/trajectory", "surround_obstacle_checker/trajectory"), ], parameters=[ obstacle_velocity_planner_param, ], - extra_arguments=[ - {'use_intra_process_comms': LaunchConfiguration('use_intra_process')} - ], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) # obstacle stop planner