Skip to content

Commit 1069e18

Browse files
authoredJul 3, 2024··
feat(autoware_behavior_path_planner): remove max_module_size param (#7764)
* feat(behavior_path_planner): remove max_module_size param The max_module_size param has been removed from the behavior_path_planner scene_module_manager.param.yaml file. This param was unnecessary and has been removed to simplify the configuration. Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp> --------- Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp>
1 parent 85095c1 commit 1069e18

File tree

4 files changed

+10
-16
lines changed

4 files changed

+10
-16
lines changed
 

‎planning/behavior_path_planner/autoware_behavior_path_planner/config/scene_module_manager.param.yaml

-11
Original file line numberDiff line numberDiff line change
@@ -9,79 +9,69 @@
99
enable_simultaneous_execution_as_candidate_module: true
1010
keep_last: false
1111
priority: 6
12-
max_module_size: 1
1312

1413
external_request_lane_change_right:
1514
enable_rtc: false
1615
enable_simultaneous_execution_as_approved_module: false
1716
enable_simultaneous_execution_as_candidate_module: true
1817
keep_last: false
1918
priority: 6
20-
max_module_size: 1
2119

2220
lane_change_left:
2321
enable_rtc: false
2422
enable_simultaneous_execution_as_approved_module: true
2523
enable_simultaneous_execution_as_candidate_module: true
2624
keep_last: false
2725
priority: 5
28-
max_module_size: 1
2926

3027
lane_change_right:
3128
enable_rtc: false
3229
enable_simultaneous_execution_as_approved_module: true
3330
enable_simultaneous_execution_as_candidate_module: true
3431
keep_last: false
3532
priority: 5
36-
max_module_size: 1
3733

3834
start_planner:
3935
enable_rtc: false
4036
enable_simultaneous_execution_as_approved_module: false
4137
enable_simultaneous_execution_as_candidate_module: false
4238
keep_last: false
4339
priority: 0
44-
max_module_size: 1
4540

4641
side_shift:
4742
enable_rtc: false
4843
enable_simultaneous_execution_as_approved_module: false
4944
enable_simultaneous_execution_as_candidate_module: false
5045
keep_last: false
5146
priority: 2
52-
max_module_size: 1
5347

5448
goal_planner:
5549
enable_rtc: false
5650
enable_simultaneous_execution_as_approved_module: false
5751
enable_simultaneous_execution_as_candidate_module: false
5852
keep_last: true
5953
priority: 1
60-
max_module_size: 1
6154

6255
static_obstacle_avoidance:
6356
enable_rtc: false
6457
enable_simultaneous_execution_as_approved_module: true
6558
enable_simultaneous_execution_as_candidate_module: false
6659
keep_last: false
6760
priority: 4
68-
max_module_size: 1
6961

7062
avoidance_by_lane_change:
7163
enable_rtc: false
7264
enable_simultaneous_execution_as_approved_module: false
7365
enable_simultaneous_execution_as_candidate_module: false
7466
keep_last: false
7567
priority: 3
76-
max_module_size: 1
7768

7869
dynamic_obstacle_avoidance:
7970
enable_rtc: false
8071
enable_simultaneous_execution_as_approved_module: true
8172
enable_simultaneous_execution_as_candidate_module: true
8273
keep_last: false
8374
priority: 7
84-
max_module_size: 1
8575

8676
sampling_planner:
8777
enable_module: true
@@ -90,4 +80,3 @@
9080
enable_simultaneous_execution_as_candidate_module: false
9181
keep_last: true
9282
priority: 16
93-
max_module_size: 1

‎planning/behavior_path_planner/autoware_behavior_path_planner/docs/behavior_path_planner_manager_design.md

-2
Original file line numberDiff line numberDiff line change
@@ -88,7 +88,6 @@ struct ModuleConfigParameters
8888
bool enable_simultaneous_execution_as_approved_module{false};
8989
bool enable_simultaneous_execution_as_candidate_module{false};
9090
uint8_t priority{0};
91-
uint8_t max_module_size{0};
9291
};
9392
```
9493

@@ -101,7 +100,6 @@ Code is [here](https://github.com/autowarefoundation/autoware.universe/blob/b173
101100
| `enable_simultaneous_execution_as_candidate_module` | bool | if true, the manager allows its scene modules to run with other scene modules as **candidate module**. |
102101
| `enable_simultaneous_execution_as_approved_module` | bool | if true, the manager allows its scene modules to run with other scene modules as **approved module**. |
103102
| `priority` | uint8_t | the manager decides execution priority based on this parameter. The smaller the number is, the higher the priority is. |
104-
| `max_module_size` | uint8_t | the sub-manager can run some modules simultaneously. this parameter set the maximum number of the launched modules. |
105103

106104
### Scene modules
107105

‎planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_manager_interface.hpp

+10-2
Original file line numberDiff line numberDiff line change
@@ -205,7 +205,16 @@ class SceneModuleManagerInterface
205205
});
206206
}
207207

208-
bool canLaunchNewModule() const { return observers_.size() < config_.max_module_size; }
208+
/**
209+
* Determine if a new module can be launched. It ensures that only one instance of a particular
210+
* scene module type is registered at a time.
211+
*
212+
* When this returns true:
213+
* - A new instance of the scene module can be launched.
214+
* - No other instance of the same name of scene module is currently active or registered.
215+
*
216+
*/
217+
bool canLaunchNewModule() const { return observers_.empty(); }
209218

210219
/**
211220
* Determine if the module is always executable, regardless of the state of other modules.
@@ -290,7 +299,6 @@ class SceneModuleManagerInterface
290299
*node, ns + "enable_simultaneous_execution_as_candidate_module");
291300
config_.keep_last = getOrDeclareParameter<bool>(*node, ns + "keep_last");
292301
config_.priority = getOrDeclareParameter<int>(*node, ns + "priority");
293-
config_.max_module_size = getOrDeclareParameter<int>(*node, ns + "max_module_size");
294302
}
295303

296304
// init rtc configuration

‎planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/parameters.hpp

-1
Original file line numberDiff line numberDiff line change
@@ -25,7 +25,6 @@ struct ModuleConfigParameters
2525
bool enable_simultaneous_execution_as_candidate_module{false};
2626
bool keep_last{false};
2727
uint8_t priority{0};
28-
uint8_t max_module_size{0};
2928
};
3029

3130
struct BehaviorPathPlannerParameters

0 commit comments

Comments
 (0)
Please sign in to comment.