Skip to content

Commit

Permalink
feat(behavior_planning): add behavior_path_planner_type to launch pat…
Browse files Browse the repository at this point in the history
…h_generator (autowarefoundation#10217)

Signed-off-by: kosuke55 <kosuke.tnp@gmail.com>
  • Loading branch information
kosuke55 committed Mar 4, 2025
1 parent 25a1e0b commit c949559
Showing 1 changed file with 60 additions and 41 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
<arg name="enable_all_modules_auto_mode"/>
<arg name="is_simulation"/>

<arg name="behavior_path_planner_type" default="behavior_path_planner" description="'behavior_path_planner' or 'path_generator'"/>
<arg name="launch_static_obstacle_avoidance" default="true"/>
<arg name="launch_avoidance_by_lane_change_module" default="true"/>
<arg name="launch_dynamic_obstacle_avoidance" default="true"/>
Expand Down Expand Up @@ -170,46 +171,8 @@
<let name="behavior_velocity_planner_launch_modules" value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + '$(var launch_module_list_end)'&quot;)"/>

<node_container pkg="rclcpp_components" exec="$(var container_type)" name="behavior_planning_container" namespace="" args="" output="both">
<composable_node pkg="autoware_behavior_path_planner" plugin="autoware::behavior_path_planner::BehaviorPathPlannerNode" name="behavior_path_planner" namespace="">
<!-- topic remap -->
<remap from="~/input/route" to="$(var input_route_topic_name)"/>
<remap from="~/input/vector_map" to="$(var input_vector_map_topic_name)"/>
<remap from="~/input/perception" to="/perception/object_recognition/objects"/>
<remap from="~/input/occupancy_grid_map" to="/perception/occupancy_grid_map/map"/>
<remap from="~/input/costmap" to="/planning/scenario_planning/parking/costmap_generator/occupancy_grid"/>
<remap from="~/input/traffic_signals" to="$(var input_traffic_light_topic_name)"/>
<remap from="~/input/odometry" to="/localization/kinematic_state"/>
<remap from="~/input/accel" to="/localization/acceleration"/>
<remap from="~/input/scenario" to="/planning/scenario_planning/scenario"/>
<remap from="~/output/path" to="path_with_lane_id"/>
<remap from="~/output/turn_indicators_cmd" to="/planning/turn_indicators_cmd"/>
<remap from="~/output/hazard_lights_cmd" to="/planning/hazard_lights_cmd"/>
<remap from="~/output/modified_goal" to="/planning/scenario_planning/modified_goal"/>
<remap from="~/output/stop_reasons" to="/planning/scenario_planning/status/stop_reasons"/>
<!-- params -->
<param from="$(var common_param_path)"/>
<param from="$(var vehicle_param_file)"/>
<param from="$(var nearest_search_param_path)"/>
<param name="launch_modules" value="$(var behavior_path_planner_launch_modules)"/>
<param name="enable_all_modules_auto_mode" value="$(var enable_all_modules_auto_mode)"/>
<param name="is_simulation" value="$(var is_simulation)"/>
<param from="$(var behavior_path_planner_side_shift_module_param_path)"/>
<param from="$(var behavior_path_planner_static_obstacle_avoidance_module_param_path)"/>
<param from="$(var behavior_path_planner_avoidance_by_lc_module_param_path)"/>
<param from="$(var behavior_path_planner_dynamic_obstacle_avoidance_module_param_path)"/>
<param from="$(var behavior_path_planner_lane_change_module_param_path)"/>
<param from="$(var behavior_path_planner_goal_planner_module_param_path)"/>
<param from="$(var behavior_path_planner_start_planner_module_param_path)"/>
<param from="$(var behavior_path_planner_sampling_planner_module_param_path)"/>
<param from="$(var behavior_path_planner_drivable_area_expansion_param_path)"/>
<param from="$(var behavior_path_planner_scene_module_manager_param_path)"/>
<param from="$(var behavior_path_planner_common_param_path)"/>
<!-- composable node config -->
<extra_arg name="use_intra_process_comms" value="false"/>
</composable_node>

<composable_node pkg="autoware_glog_component" plugin="autoware::glog_component::GlogComponent" name="glog_component" namespace=""/>
<composable_node pkg="autoware_behavior_velocity_planner" plugin="autoware::behavior_velocity_planner::BehaviorVelocityPlannerNode" name="behavior_velocity_planner" namespace="">
<!-- topic remap -->
<remap from="~/input/path_with_lane_id" to="path_with_lane_id"/>
<remap from="~/input/vector_map" to="$(var input_vector_map_topic_name)"/>
<remap from="~/input/vehicle_odometry" to="/localization/kinematic_state"/>
Expand Down Expand Up @@ -254,10 +217,66 @@
<!-- composable node config -->
<extra_arg name="use_intra_process_comms" value="false"/>
</composable_node>

<composable_node pkg="autoware_glog_component" plugin="autoware::glog_component::GlogComponent" name="glog_component" namespace=""/>
</node_container>

<group if="$(eval &quot;'$(var behavior_path_planner_type)' == 'behavior_path_planner'&quot;)">
<load_composable_node target="/planning/scenario_planning/lane_driving/behavior_planning/behavior_planning_container">
<composable_node pkg="autoware_behavior_path_planner" plugin="autoware::behavior_path_planner::BehaviorPathPlannerNode" name="behavior_path_planner" namespace="">
<remap from="~/input/route" to="$(var input_route_topic_name)"/>
<remap from="~/input/vector_map" to="$(var input_vector_map_topic_name)"/>
<remap from="~/input/perception" to="/perception/object_recognition/objects"/>
<remap from="~/input/occupancy_grid_map" to="/perception/occupancy_grid_map/map"/>
<remap from="~/input/costmap" to="/planning/scenario_planning/parking/costmap_generator/occupancy_grid"/>
<remap from="~/input/traffic_signals" to="$(var input_traffic_light_topic_name)"/>
<remap from="~/input/odometry" to="/localization/kinematic_state"/>
<remap from="~/input/accel" to="/localization/acceleration"/>
<remap from="~/input/scenario" to="/planning/scenario_planning/scenario"/>
<remap from="~/output/path" to="path_with_lane_id"/>
<remap from="~/output/turn_indicators_cmd" to="/planning/turn_indicators_cmd"/>
<remap from="~/output/hazard_lights_cmd" to="/planning/hazard_lights_cmd"/>
<remap from="~/output/modified_goal" to="/planning/scenario_planning/modified_goal"/>
<remap from="~/output/stop_reasons" to="/planning/scenario_planning/status/stop_reasons"/>
<!-- params -->
<param from="$(var common_param_path)"/>
<param from="$(var vehicle_param_file)"/>
<param from="$(var nearest_search_param_path)"/>
<param name="launch_modules" value="$(var behavior_path_planner_launch_modules)"/>
<param name="enable_all_modules_auto_mode" value="$(var enable_all_modules_auto_mode)"/>
<param name="is_simulation" value="$(var is_simulation)"/>
<param from="$(var behavior_path_planner_side_shift_module_param_path)"/>
<param from="$(var behavior_path_planner_static_obstacle_avoidance_module_param_path)"/>
<param from="$(var behavior_path_planner_avoidance_by_lc_module_param_path)"/>
<param from="$(var behavior_path_planner_dynamic_obstacle_avoidance_module_param_path)"/>
<param from="$(var behavior_path_planner_lane_change_module_param_path)"/>
<param from="$(var behavior_path_planner_goal_planner_module_param_path)"/>
<param from="$(var behavior_path_planner_start_planner_module_param_path)"/>
<param from="$(var behavior_path_planner_sampling_planner_module_param_path)"/>
<param from="$(var behavior_path_planner_drivable_area_expansion_param_path)"/>
<param from="$(var behavior_path_planner_scene_module_manager_param_path)"/>
<param from="$(var behavior_path_planner_common_param_path)"/>
<!-- composable node config -->
<extra_arg name="use_intra_process_comms" value="false"/>
</composable_node>
</load_composable_node>
</group>

<group if="$(eval &quot;'$(var behavior_path_planner_type)' == 'path_generator'&quot;)">
<load_composable_node target="/planning/scenario_planning/lane_driving/behavior_planning/behavior_planning_container">
<composable_node pkg="autoware_path_generator" plugin="autoware::path_generator::PathGenerator" name="path_generator" namespace="">
<remap from="~/input/route" to="$(var input_route_topic_name)"/>
<remap from="~/input/vector_map" to="$(var input_vector_map_topic_name)"/>
<remap from="~/input/odometry" to="/localization/kinematic_state"/>
<remap from="~/output/path" to="path_with_lane_id"/>
<!-- params -->
<param from="$(var vehicle_param_file)"/>
<param from="$(var nearest_search_param_path)"/>
<param from="$(var path_generator_param_path)"/>
<!-- composable node config -->
<extra_arg name="use_intra_process_comms" value="false"/>
</composable_node>
</load_composable_node>
</group>

<group if="$(var launch_compare_map_pipeline)">
<!-- use pointcloud container -->
<load_composable_node target="$(var pointcloud_container_name)">
Expand Down

0 comments on commit c949559

Please sign in to comment.