30
30
31
31
namespace autoware ::behavior_path_planner
32
32
{
33
- PlannerManager::PlannerManager (rclcpp::Node & node, const size_t max_iteration_num )
33
+ PlannerManager::PlannerManager (rclcpp::Node & node)
34
34
: plugin_loader_(
35
35
" autoware_behavior_path_planner" ,
36
36
" autoware::behavior_path_planner::SceneModuleManagerInterface" ),
37
37
logger_ (node.get_logger().get_child(" planner_manager" )),
38
- clock_(*node.get_clock()),
39
- max_iteration_num_{max_iteration_num}
38
+ clock_(*node.get_clock())
40
39
{
41
40
processing_time_.emplace (" total_time" , 0.0 );
42
41
debug_publisher_ptr_ = std::make_unique<DebugPublisher>(&node, " ~/debug" );
@@ -66,6 +65,11 @@ void PlannerManager::launchScenePlugin(rclcpp::Node & node, const std::string &
66
65
}
67
66
}
68
67
68
+ void PlannerManager::calculateMaxIterationNum (const size_t scene_module_num)
69
+ {
70
+ max_iteration_num_ = scene_module_num * (scene_module_num + 1 ) / 2 ;
71
+ }
72
+
69
73
void PlannerManager::removeScenePlugin (rclcpp::Node & node, const std::string & name)
70
74
{
71
75
auto it = std::remove_if (manager_ptrs_.begin (), manager_ptrs_.end (), [&](const auto plugin) {
@@ -127,17 +131,19 @@ BehaviorModuleOutput PlannerManager::run(const std::shared_ptr<PlannerData> & da
127
131
" Ego is out of route, no module is running. Skip running scene modules." );
128
132
return output;
129
133
}
134
+ std::vector<SceneModulePtr>
135
+ deleted_modules; // store the scene modules deleted from approved modules
130
136
131
137
for (size_t itr_num = 1 ;; ++itr_num) {
132
138
/* *
133
139
* STEP1: get approved modules' output
134
140
*/
135
- auto approved_modules_output = runApprovedModules (data);
141
+ auto approved_modules_output = runApprovedModules (data, deleted_modules );
136
142
137
143
/* *
138
144
* STEP2: check modules that need to be launched
139
145
*/
140
- const auto request_modules = getRequestModules (approved_modules_output);
146
+ const auto request_modules = getRequestModules (approved_modules_output, deleted_modules );
141
147
142
148
/* *
143
149
* STEP3: if there is no module that need to be launched, return approved modules' output
@@ -250,7 +256,8 @@ void PlannerManager::generateCombinedDrivableArea(
250
256
}
251
257
252
258
std::vector<SceneModulePtr> PlannerManager::getRequestModules (
253
- const BehaviorModuleOutput & previous_module_output) const
259
+ const BehaviorModuleOutput & previous_module_output,
260
+ const std::vector<SceneModulePtr> & deleted_modules) const
254
261
{
255
262
if (previous_module_output.path .points .empty ()) {
256
263
RCLCPP_ERROR_STREAM (
@@ -268,6 +275,18 @@ std::vector<SceneModulePtr> PlannerManager::getRequestModules(
268
275
269
276
for (const auto & manager_ptr : manager_ptrs_) {
270
277
stop_watch_.tic (manager_ptr->name ());
278
+ /* *
279
+ * skip the module that is already deleted.
280
+ */
281
+ {
282
+ const auto name = manager_ptr->name ();
283
+ const auto find_deleted_module = [&name](const auto & m) { return m->name () == name; };
284
+ const auto itr =
285
+ std::find_if (deleted_modules.begin (), deleted_modules.end (), find_deleted_module);
286
+ if (itr != deleted_modules.end ()) {
287
+ continue ;
288
+ }
289
+ }
271
290
272
291
/* *
273
292
* determine the execution capability of modules based on existing approved modules.
@@ -655,7 +674,8 @@ std::pair<SceneModulePtr, BehaviorModuleOutput> PlannerManager::runRequestModule
655
674
return std::make_pair (module_ptr, results.at (module_ptr->name ()));
656
675
}
657
676
658
- BehaviorModuleOutput PlannerManager::runApprovedModules (const std::shared_ptr<PlannerData> & data)
677
+ BehaviorModuleOutput PlannerManager::runApprovedModules (
678
+ const std::shared_ptr<PlannerData> & data, std::vector<SceneModulePtr> & deleted_modules)
659
679
{
660
680
std::unordered_map<std::string, BehaviorModuleOutput> results;
661
681
BehaviorModuleOutput output = getReferencePath (data);
@@ -771,6 +791,9 @@ BehaviorModuleOutput PlannerManager::runApprovedModules(const std::shared_ptr<Pl
771
791
const auto itr = std::find_if (
772
792
approved_module_ptrs_.begin (), approved_module_ptrs_.end (),
773
793
[](const auto & m) { return m->getCurrentStatus () == ModuleStatus::FAILURE; });
794
+ if (itr != approved_module_ptrs_.end ()) {
795
+ deleted_modules.push_back (*itr);
796
+ }
774
797
775
798
std::for_each (itr, approved_module_ptrs_.end (), [this ](auto & m) {
776
799
debug_info_.emplace_back (m, Action::DELETE, " From Approved" );
@@ -842,6 +865,9 @@ BehaviorModuleOutput PlannerManager::runApprovedModules(const std::shared_ptr<Pl
842
865
}))
843
866
resetCurrentRouteLanelet (data);
844
867
868
+ std::copy_if (
869
+ itr, approved_module_ptrs_.end (), std::back_inserter (deleted_modules), success_module_cond);
870
+
845
871
std::for_each (itr, approved_module_ptrs_.end (), [&](auto & m) {
846
872
debug_info_.emplace_back (m, Action::DELETE, " From Approved" );
847
873
deleteExpiredModules (m);
0 commit comments