Skip to content

Commit f4bbb8b

Browse files
committed
fix(bpp): don't remove rtc cooperate status
Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>
1 parent 39bac29 commit f4bbb8b

File tree

6 files changed

+1
-15
lines changed

6 files changed

+1
-15
lines changed

planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/scene.hpp

-1
Original file line numberDiff line numberDiff line change
@@ -365,7 +365,6 @@ class AvoidanceModule : public SceneModuleInterface
365365
if (!path_shifter_.getShiftLines().empty()) {
366366
left_shift_array_.clear();
367367
right_shift_array_.clear();
368-
removeRTCStatus();
369368
}
370369

371370
generator_.reset();

planning/behavior_path_avoidance_module/src/scene.cpp

-1
Original file line numberDiff line numberDiff line change
@@ -1283,7 +1283,6 @@ void AvoidanceModule::updateData()
12831283
void AvoidanceModule::processOnEntry()
12841284
{
12851285
initVariables();
1286-
removeRTCStatus();
12871286
}
12881287

12891288
void AvoidanceModule::processOnExit()

planning/behavior_path_lane_change_module/src/interface.cpp

-2
Original file line numberDiff line numberDiff line change
@@ -117,7 +117,6 @@ BehaviorModuleOutput LaneChangeInterface::plan()
117117
updateSteeringFactorPtr(output);
118118
if (module_type_->isAbortState()) {
119119
waitApproval();
120-
removeRTCStatus();
121120
const auto candidate = planCandidate();
122121
path_candidate_ = std::make_shared<PathWithLaneId>(candidate.path_candidate);
123122
updateRTCStatus(
@@ -147,7 +146,6 @@ BehaviorModuleOutput LaneChangeInterface::planWaitingApproval()
147146
stop_pose_ = module_type_->getStopPose();
148147

149148
if (!module_type_->isValidPath()) {
150-
removeRTCStatus();
151149
path_candidate_ = std::make_shared<PathWithLaneId>();
152150
return out;
153151
}

planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_interface.hpp

-10
Original file line numberDiff line numberDiff line change
@@ -187,7 +187,6 @@ class SceneModuleInterface
187187
RCLCPP_DEBUG(getLogger(), "%s %s", name_.c_str(), __func__);
188188

189189
clearWaitingApproval();
190-
removeRTCStatus();
191190
unlockNewModuleLaunch();
192191
unlockOutputPath();
193192
steering_factor_interface_ptr_->clearSteeringFactors();
@@ -527,15 +526,6 @@ class SceneModuleInterface
527526
return existApprovedRequest();
528527
}
529528

530-
void removeRTCStatus()
531-
{
532-
for (const auto & [module_name, ptr] : rtc_interface_ptr_map_) {
533-
if (ptr) {
534-
ptr->clearCooperateStatus();
535-
}
536-
}
537-
}
538-
539529
void setStopReason(const std::string & stop_reason, const PathWithLaneId & path)
540530
{
541531
stop_reason_.reason = stop_reason;

planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_manager_interface.hpp

+1
Original file line numberDiff line numberDiff line change
@@ -103,6 +103,7 @@ class SceneModuleManagerInterface
103103
{
104104
for (const auto & [module_name, ptr] : rtc_interface_ptr_map_) {
105105
if (ptr) {
106+
ptr->removeExpiredCooperateStatus();
106107
ptr->publishCooperateStatus(rclcpp::Clock(RCL_ROS_TIME).now());
107108
}
108109
}

planning/behavior_path_start_planner_module/src/start_planner_module.cpp

-1
Original file line numberDiff line numberDiff line change
@@ -1051,7 +1051,6 @@ void StartPlannerModule::updateStatusAfterBackwardDriving()
10511051
// request start_planner approval
10521052
waitApproval();
10531053
// To enable approval of the forward path, the RTC status is removed.
1054-
removeRTCStatus();
10551054
for (auto itr = uuid_map_.begin(); itr != uuid_map_.end(); ++itr) {
10561055
itr->second = generateUUID();
10571056
}

0 commit comments

Comments
 (0)