diff --git a/planning/behavior_velocity_planner/include/scene_module/crosswalk/manager.hpp b/planning/behavior_velocity_planner/include/scene_module/crosswalk/manager.hpp index 5234dedfeb171..c4355a04e49d9 100644 --- a/planning/behavior_velocity_planner/include/scene_module/crosswalk/manager.hpp +++ b/planning/behavior_velocity_planner/include/scene_module/crosswalk/manager.hpp @@ -40,7 +40,6 @@ class CrosswalkModuleManager : public SceneModuleManagerInterfaceWithRTC private: CrosswalkModule::PlannerParam crosswalk_planner_param_; WalkwayModule::PlannerParam walkway_planner_param_; - rtc_interface::RTCInterface rtc_interface_; std::vector getCrosswalksOnPath( const autoware_auto_planning_msgs::msg::PathWithLaneId & path, @@ -51,7 +50,7 @@ class CrosswalkModuleManager : public SceneModuleManagerInterfaceWithRTC const autoware_auto_planning_msgs::msg::PathWithLaneId & path, const lanelet::LaneletMapPtr lanelet_map, const std::shared_ptr & overall_graphs); - + void launchNewModules(const autoware_auto_planning_msgs::msg::PathWithLaneId & path) override; std::function &)> getModuleExpiredFunction( diff --git a/planning/behavior_velocity_planner/include/scene_module/scene_module_interface.hpp b/planning/behavior_velocity_planner/include/scene_module/scene_module_interface.hpp index eaa451fb2957e..9bfab12b2f0e5 100644 --- a/planning/behavior_velocity_planner/include/scene_module/scene_module_interface.hpp +++ b/planning/behavior_velocity_planner/include/scene_module/scene_module_interface.hpp @@ -17,10 +17,9 @@ #include "behavior_velocity_planner/planner_data.hpp" - -#include #include #include +#include #include #include diff --git a/planning/behavior_velocity_planner/src/scene_module/crosswalk/manager.cpp b/planning/behavior_velocity_planner/src/scene_module/crosswalk/manager.cpp index c9c191eaa540e..063b1cb820c4c 100644 --- a/planning/behavior_velocity_planner/src/scene_module/crosswalk/manager.cpp +++ b/planning/behavior_velocity_planner/src/scene_module/crosswalk/manager.cpp @@ -22,7 +22,7 @@ namespace behavior_velocity_planner { CrosswalkModuleManager::CrosswalkModuleManager(rclcpp::Node & node) -: SceneModuleManagerInterface(node, getModuleName()) +: SceneModuleManagerInterfaceWithRTC(node, getModuleName()) { const std::string ns(getModuleName()); @@ -105,31 +105,6 @@ std::set CrosswalkModuleManager::getCrosswalkIdSetOnPath( return crosswalk_id_set; } -} // namespace - -CrosswalkModuleManager::CrosswalkModuleManager(rclcpp::Node & node) -: SceneModuleManagerInterfaceWithRTC(node, getModuleName()) -{ - const std::string ns(getModuleName()); - - // for crosswalk parameters - auto & cp = crosswalk_planner_param_; - cp.stop_line_distance = node.declare_parameter(ns + ".crosswalk.stop_line_distance", 1.5); - cp.stop_margin = node.declare_parameter(ns + ".crosswalk.stop_margin", 1.0); - cp.slow_margin = node.declare_parameter(ns + ".crosswalk.slow_margin", 2.0); - cp.slow_velocity = node.declare_parameter(ns + ".crosswalk.slow_velocity", 5.0 / 3.6); - cp.stop_predicted_object_prediction_time_margin = - node.declare_parameter(ns + ".crosswalk.stop_predicted_object_prediction_time_margin", 3.0); - cp.external_input_timeout = node.declare_parameter(ns + ".crosswalk.external_input_timeout", 1.0); - - // for walkway parameters - auto & wp = walkway_planner_param_; - wp.stop_margin = node.declare_parameter(ns + ".walkway.stop_margin", 1.0); - wp.stop_line_distance = node.declare_parameter(ns + ".walkway.stop_line_distance", 1.0); - wp.stop_duration_sec = node.declare_parameter(ns + ".walkway.stop_duration_sec", 1.0); - wp.external_input_timeout = node.declare_parameter(ns + ".walkway.external_input_timeout", 1.0); -} - void CrosswalkModuleManager::launchNewModules( const autoware_auto_planning_msgs::msg::PathWithLaneId & path) {