diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/config/scene_module_manager.param.yaml b/planning/behavior_path_planner/autoware_behavior_path_planner/config/scene_module_manager.param.yaml index 6cf8719b2ef83..ef6cb82d1412a 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner/config/scene_module_manager.param.yaml +++ b/planning/behavior_path_planner/autoware_behavior_path_planner/config/scene_module_manager.param.yaml @@ -9,7 +9,6 @@ enable_simultaneous_execution_as_candidate_module: true keep_last: false priority: 6 - max_module_size: 1 external_request_lane_change_right: enable_rtc: false @@ -17,7 +16,6 @@ enable_simultaneous_execution_as_candidate_module: true keep_last: false priority: 6 - max_module_size: 1 lane_change_left: enable_rtc: false @@ -25,7 +23,6 @@ enable_simultaneous_execution_as_candidate_module: true keep_last: false priority: 5 - max_module_size: 1 lane_change_right: enable_rtc: false @@ -33,7 +30,6 @@ enable_simultaneous_execution_as_candidate_module: true keep_last: false priority: 5 - max_module_size: 1 start_planner: enable_rtc: false @@ -41,7 +37,6 @@ enable_simultaneous_execution_as_candidate_module: false keep_last: false priority: 0 - max_module_size: 1 side_shift: enable_rtc: false @@ -49,7 +44,6 @@ enable_simultaneous_execution_as_candidate_module: false keep_last: false priority: 2 - max_module_size: 1 goal_planner: enable_rtc: false @@ -57,7 +51,6 @@ enable_simultaneous_execution_as_candidate_module: false keep_last: true priority: 1 - max_module_size: 1 static_obstacle_avoidance: enable_rtc: false @@ -65,7 +58,6 @@ enable_simultaneous_execution_as_candidate_module: false keep_last: false priority: 4 - max_module_size: 1 avoidance_by_lane_change: enable_rtc: false @@ -73,7 +65,6 @@ enable_simultaneous_execution_as_candidate_module: false keep_last: false priority: 3 - max_module_size: 1 dynamic_obstacle_avoidance: enable_rtc: false @@ -81,7 +72,6 @@ enable_simultaneous_execution_as_candidate_module: true keep_last: false priority: 7 - max_module_size: 1 sampling_planner: enable_module: true @@ -90,4 +80,3 @@ enable_simultaneous_execution_as_candidate_module: false keep_last: true priority: 16 - max_module_size: 1 diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/docs/behavior_path_planner_manager_design.md b/planning/behavior_path_planner/autoware_behavior_path_planner/docs/behavior_path_planner_manager_design.md index 5ffdcafdb2497..09627d2d5d91e 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner/docs/behavior_path_planner_manager_design.md +++ b/planning/behavior_path_planner/autoware_behavior_path_planner/docs/behavior_path_planner_manager_design.md @@ -88,7 +88,6 @@ struct ModuleConfigParameters bool enable_simultaneous_execution_as_approved_module{false}; bool enable_simultaneous_execution_as_candidate_module{false}; uint8_t priority{0}; - uint8_t max_module_size{0}; }; ``` @@ -101,7 +100,6 @@ Code is [here](https://github.com/autowarefoundation/autoware.universe/blob/b173 | `enable_simultaneous_execution_as_candidate_module` | bool | if true, the manager allows its scene modules to run with other scene modules as **candidate module**. | | `enable_simultaneous_execution_as_approved_module` | bool | if true, the manager allows its scene modules to run with other scene modules as **approved module**. | | `priority` | uint8_t | the manager decides execution priority based on this parameter. The smaller the number is, the higher the priority is. | -| `max_module_size` | uint8_t | the sub-manager can run some modules simultaneously. this parameter set the maximum number of the launched modules. | ### Scene modules diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_manager_interface.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_manager_interface.hpp index 5b9c0389e29c5..fab9a6ba45113 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_manager_interface.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_manager_interface.hpp @@ -205,7 +205,16 @@ class SceneModuleManagerInterface }); } - bool canLaunchNewModule() const { return observers_.size() < config_.max_module_size; } + /** + * Determine if a new module can be launched. It ensures that only one instance of a particular + * scene module type is registered at a time. + * + * When this returns true: + * - A new instance of the scene module can be launched. + * - No other instance of the same name of scene module is currently active or registered. + * + */ + bool canLaunchNewModule() const { return observers_.empty(); } /** * Determine if the module is always executable, regardless of the state of other modules. @@ -290,7 +299,6 @@ class SceneModuleManagerInterface *node, ns + "enable_simultaneous_execution_as_candidate_module"); config_.keep_last = getOrDeclareParameter(*node, ns + "keep_last"); config_.priority = getOrDeclareParameter(*node, ns + "priority"); - config_.max_module_size = getOrDeclareParameter(*node, ns + "max_module_size"); } // init rtc configuration diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/parameters.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/parameters.hpp index bbc249f5a0daf..a45e8366f45d8 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/parameters.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/parameters.hpp @@ -25,7 +25,6 @@ struct ModuleConfigParameters bool enable_simultaneous_execution_as_candidate_module{false}; bool keep_last{false}; uint8_t priority{0}; - uint8_t max_module_size{0}; }; struct BehaviorPathPlannerParameters