diff --git a/system/autoware_default_adapi/src/planning.cpp b/system/autoware_default_adapi/src/planning.cpp index 4ff0edfd2b7d5..d89ef6c221666 100644 --- a/system/autoware_default_adapi/src/planning.cpp +++ b/system/autoware_default_adapi/src/planning.cpp @@ -87,7 +87,14 @@ PlanningNode::PlanningNode(const rclcpp::NodeOptions & options) : Node("planning "/planning/velocity_factors/traffic_light", "/planning/velocity_factors/virtual_traffic_light", "/planning/velocity_factors/walkway", - "/planning/velocity_factors/motion_velocity_planner"}; + "/planning/velocity_factors/motion_velocity_planner", + "/planning/velocity_factors/static_obstacle_avoidance", + "/planning/velocity_factors/dynamic_obstacle_avoidance", + "/planning/velocity_factors/avoidance_by_lane_change", + "/planning/velocity_factors/lane_change_left", + "/planning/velocity_factors/lane_change_right", + "/planning/velocity_factors/start_planner", + "/planning/velocity_factors/goal_planner"}; std::vector steering_factor_topics = { "/planning/steering_factor/static_obstacle_avoidance",