Skip to content

Commit ef0569f

Browse files
authored
refactor(side_shift): support new interface (#5556)
Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>
1 parent 60a51e0 commit ef0569f

File tree

2 files changed

+7
-33
lines changed

2 files changed

+7
-33
lines changed

planning/behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/side_shift_module.hpp

+2-24
Original file line numberDiff line numberDiff line change
@@ -49,8 +49,6 @@ class SideShiftModule : public SceneModuleInterface
4949
bool isExecutionReady() const override;
5050
bool isReadyForNextRequest(
5151
const double & min_request_time_sec, bool override_requests = false) const noexcept;
52-
// TODO(someone): remove this, and use base class function
53-
[[deprecated]] ModuleStatus updateState() override;
5452
void updateData() override;
5553
BehaviorModuleOutput plan() override;
5654
BehaviorModuleOutput planWaitingApproval() override;
@@ -70,32 +68,12 @@ class SideShiftModule : public SceneModuleInterface
7068
{
7169
}
7270

73-
// TODO(someone): remove this, and use base class function
74-
[[deprecated]] BehaviorModuleOutput run() override
75-
{
76-
updateData();
77-
78-
if (!isWaitingApproval()) {
79-
return plan();
80-
}
81-
82-
// module is waiting approval. Check it.
83-
if (isActivated()) {
84-
RCLCPP_DEBUG(getLogger(), "Was waiting approval, and now approved. Do plan().");
85-
return plan();
86-
} else {
87-
RCLCPP_DEBUG(getLogger(), "keep waiting approval... Do planCandidate().");
88-
return planWaitingApproval();
89-
}
90-
}
91-
9271
private:
93-
bool canTransitSuccessState() override { return false; }
72+
bool canTransitSuccessState() override;
9473

9574
bool canTransitFailureState() override { return false; }
9675

97-
bool canTransitIdleToRunningState() override { return false; }
98-
rclcpp::Subscription<LateralOffset>::SharedPtr lateral_offset_subscriber_;
76+
bool canTransitIdleToRunningState() override { return true; }
9977

10078
void initVariables();
10179

planning/behavior_path_planner/src/scene_module/side_shift/side_shift_module.cpp

+5-9
Original file line numberDiff line numberDiff line change
@@ -40,8 +40,6 @@ SideShiftModule::SideShiftModule(
4040
const std::unordered_map<std::string, std::shared_ptr<RTCInterface> > & rtc_interface_ptr_map)
4141
: SceneModuleInterface{name, node, rtc_interface_ptr_map}, parameters_{parameters}
4242
{
43-
// If lateral offset is subscribed, it approves side shift module automatically
44-
clearWaitingApproval();
4543
}
4644

4745
void SideShiftModule::initVariables()
@@ -80,7 +78,7 @@ void SideShiftModule::setParameters(const std::shared_ptr<SideShiftParameters> &
8078

8179
bool SideShiftModule::isExecutionRequested() const
8280
{
83-
if (current_state_ == ModuleStatus::RUNNING) {
81+
if (getCurrentStatus() == ModuleStatus::RUNNING) {
8482
return true;
8583
}
8684

@@ -112,7 +110,7 @@ bool SideShiftModule::isReadyForNextRequest(
112110
return false;
113111
}
114112

115-
ModuleStatus SideShiftModule::updateState()
113+
bool SideShiftModule::canTransitSuccessState()
116114
{
117115
// Never return the FAILURE. When the desired offset is zero and the vehicle is in the original
118116
// drivable area,this module can stop the computation and return SUCCESS.
@@ -150,7 +148,7 @@ ModuleStatus SideShiftModule::updateState()
150148
no_shifted_plan);
151149

152150
if (no_request && no_shifted_plan && no_offset_diff) {
153-
return ModuleStatus::SUCCESS;
151+
return true;
154152
}
155153

156154
const auto & current_lanes = utils::getCurrentLanes(planner_data_);
@@ -169,7 +167,7 @@ ModuleStatus SideShiftModule::updateState()
169167
} else {
170168
shift_status_ = SideShiftStatus::AFTER_SHIFT;
171169
}
172-
return ModuleStatus::RUNNING;
170+
return false;
173171
}
174172

175173
void SideShiftModule::updateData()
@@ -184,7 +182,7 @@ void SideShiftModule::updateData()
184182
}
185183
}
186184

187-
if (current_state_ != ModuleStatus::RUNNING && current_state_ != ModuleStatus::IDLE) {
185+
if (getCurrentStatus() != ModuleStatus::RUNNING && getCurrentStatus() != ModuleStatus::IDLE) {
188186
return;
189187
}
190188

@@ -331,8 +329,6 @@ BehaviorModuleOutput SideShiftModule::planWaitingApproval()
331329

332330
prev_output_ = shifted_path;
333331

334-
waitApproval();
335-
336332
return output;
337333
}
338334

0 commit comments

Comments
 (0)