Skip to content

Commit

Permalink
launch behavior planning as 2 normal nodes rather than composable nodes
Browse files Browse the repository at this point in the history
Signed-off-by: Maxime CLEMENT <[email protected]>
  • Loading branch information
maxime-clem committed Feb 3, 2024
1 parent c89f863 commit 8856575
Showing 1 changed file with 77 additions and 85 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -174,92 +174,84 @@
/>
<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="screen">
<composable_node pkg="behavior_path_planner" plugin="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 from="$(var behavior_path_planner_side_shift_module_param_path)"/>
<param from="$(var behavior_path_planner_avoidance_module_param_path)"/>
<param from="$(var behavior_path_planner_avoidance_by_lc_module_param_path)"/>
<param from="$(var behavior_path_planner_dynamic_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_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>
<node pkg="behavior_path_planner" exec="behavior_path_planner_node" 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 from="$(var behavior_path_planner_side_shift_module_param_path)"/>
<param from="$(var behavior_path_planner_avoidance_module_param_path)"/>
<param from="$(var behavior_path_planner_avoidance_by_lc_module_param_path)"/>
<param from="$(var behavior_path_planner_dynamic_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_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)"/>
</node>

<composable_node pkg="behavior_velocity_planner" plugin="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"/>
<remap from="~/input/accel" to="/localization/acceleration"/>
<remap from="~/input/dynamic_objects" to="/perception/object_recognition/objects"/>
<remap from="~/input/no_ground_pointcloud" to="/perception/obstacle_segmentation/pointcloud"/>
<remap from="~/input/compare_map_filtered_pointcloud" to="compare_map_filtered/pointcloud"/>
<remap from="~/input/vector_map_inside_area_filtered_pointcloud" to="vector_map_inside_area_filtered/pointcloud"/>
<remap from="~/input/external_velocity_limit_mps" to="/planning/scenario_planning/max_velocity_default"/>
<remap from="~/input/traffic_signals" to="$(var input_traffic_light_topic_name)"/>
<remap from="~/input/virtual_traffic_light_states" to="$(var input_virtual_traffic_light_topic_name)"/>
<remap from="~/input/occupancy_grid" to="/perception/occupancy_grid_map/map"/>
<remap from="~/output/path" to="path"/>
<remap from="~/output/stop_reasons" to="/planning/scenario_planning/status/stop_reasons"/>
<remap from="~/output/infrastructure_commands" to="/planning/scenario_planning/status/infrastructure_commands"/>
<remap from="~/output/traffic_signal" to="debug/traffic_signal"/>
<!-- params -->
<param from="$(var common_param_path)"/>
<param from="$(var vehicle_param_file)"/>
<param from="$(var nearest_search_param_path)"/>
<param from="$(var motion_velocity_smoother_param_path)"/>
<param from="$(var behavior_velocity_smoother_type_param_path)"/>
<param from="$(var behavior_velocity_planner_common_param_path)"/>
<param name="launch_modules" value="$(var behavior_velocity_planner_launch_modules)"/>
<param name="enable_all_modules_auto_mode" value="$(var enable_all_modules_auto_mode)"/>
<!-- <param from="$(var template_param_path)"/> -->
<param from="$(var behavior_velocity_planner_blind_spot_module_param_path)"/>
<param from="$(var behavior_velocity_planner_crosswalk_module_param_path)"/>
<param from="$(var behavior_velocity_planner_walkway_module_param_path)"/>
<param from="$(var behavior_velocity_planner_detection_area_module_param_path)"/>
<param from="$(var behavior_velocity_planner_intersection_module_param_path)"/>
<param from="$(var behavior_velocity_planner_stop_line_module_param_path)"/>
<param from="$(var behavior_velocity_planner_traffic_light_module_param_path)"/>
<param from="$(var behavior_velocity_planner_virtual_traffic_light_module_param_path)"/>
<param from="$(var behavior_velocity_planner_occlusion_spot_module_param_path)"/>
<param from="$(var behavior_velocity_planner_no_stopping_area_module_param_path)"/>
<param from="$(var behavior_velocity_planner_run_out_module_param_path)"/>
<param from="$(var behavior_velocity_planner_speed_bump_module_param_path)"/>
<param from="$(var behavior_velocity_planner_out_of_lane_module_param_path)"/>
<param from="$(var behavior_velocity_planner_no_drivable_lane_module_param_path)"/>
<param from="$(var behavior_velocity_planner_dynamic_obstacle_stop_module_param_path)"/>
<!-- composable node config -->
<extra_arg name="use_intra_process_comms" value="false"/>
</composable_node>

<composable_node pkg="glog_component" plugin="GlogComponent" name="glog_component" namespace=""/>

This comment has been minimized.

Copy link
@felixf4xu

felixf4xu Feb 4, 2024

I'm not sure what to do with glog_component here.

This comment has been minimized.

Copy link
@maxime-clem

maxime-clem Feb 4, 2024

Author Owner

glog_component is used to provide a stack trace when a node_container crashes.
Since I removed the node_container, glog_component cannot be used here.

</node_container>
<node pkg="behavior_velocity_planner" exec="behavior_velocity_planner_node" 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"/>
<remap from="~/input/accel" to="/localization/acceleration"/>
<remap from="~/input/dynamic_objects" to="/perception/object_recognition/objects"/>
<remap from="~/input/no_ground_pointcloud" to="/perception/obstacle_segmentation/pointcloud"/>
<remap from="~/input/compare_map_filtered_pointcloud" to="compare_map_filtered/pointcloud"/>
<remap from="~/input/vector_map_inside_area_filtered_pointcloud" to="vector_map_inside_area_filtered/pointcloud"/>
<remap from="~/input/external_velocity_limit_mps" to="/planning/scenario_planning/max_velocity_default"/>
<remap from="~/input/traffic_signals" to="$(var input_traffic_light_topic_name)"/>
<remap from="~/input/virtual_traffic_light_states" to="$(var input_virtual_traffic_light_topic_name)"/>
<remap from="~/input/occupancy_grid" to="/perception/occupancy_grid_map/map"/>
<remap from="~/output/path" to="path"/>
<remap from="~/output/stop_reasons" to="/planning/scenario_planning/status/stop_reasons"/>
<remap from="~/output/infrastructure_commands" to="/planning/scenario_planning/status/infrastructure_commands"/>
<remap from="~/output/traffic_signal" to="debug/traffic_signal"/>
<!-- params -->
<param from="$(var common_param_path)"/>
<param from="$(var vehicle_param_file)"/>
<param from="$(var nearest_search_param_path)"/>
<param from="$(var motion_velocity_smoother_param_path)"/>
<param from="$(var behavior_velocity_smoother_type_param_path)"/>
<param from="$(var behavior_velocity_planner_common_param_path)"/>
<param name="launch_modules" value="$(var behavior_velocity_planner_launch_modules)"/>
<param name="enable_all_modules_auto_mode" value="$(var enable_all_modules_auto_mode)"/>
<!-- <param from="$(var template_param_path)"/> -->
<param from="$(var behavior_velocity_planner_blind_spot_module_param_path)"/>
<param from="$(var behavior_velocity_planner_crosswalk_module_param_path)"/>
<param from="$(var behavior_velocity_planner_walkway_module_param_path)"/>
<param from="$(var behavior_velocity_planner_detection_area_module_param_path)"/>
<param from="$(var behavior_velocity_planner_intersection_module_param_path)"/>
<param from="$(var behavior_velocity_planner_stop_line_module_param_path)"/>
<param from="$(var behavior_velocity_planner_traffic_light_module_param_path)"/>
<param from="$(var behavior_velocity_planner_virtual_traffic_light_module_param_path)"/>
<param from="$(var behavior_velocity_planner_occlusion_spot_module_param_path)"/>
<param from="$(var behavior_velocity_planner_no_stopping_area_module_param_path)"/>
<param from="$(var behavior_velocity_planner_run_out_module_param_path)"/>
<param from="$(var behavior_velocity_planner_speed_bump_module_param_path)"/>
<param from="$(var behavior_velocity_planner_out_of_lane_module_param_path)"/>
<param from="$(var behavior_velocity_planner_no_drivable_lane_module_param_path)"/>
<param from="$(var behavior_velocity_planner_dynamic_obstacle_stop_module_param_path)"/>
</node>

<group if="$(var launch_compare_map_pipeline)">
<group if="$(var use_pointcloud_container)">
Expand Down

1 comment on commit 8856575

@felixf4xu
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

thanks, I will have a try.

Please sign in to comment.