Skip to content

Commit e98ac1c

Browse files
explicitly set the initial state
Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp>
1 parent 8e14768 commit e98ac1c

File tree

9 files changed

+12
-42
lines changed

9 files changed

+12
-42
lines changed

planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/scene.hpp

-2
Original file line numberDiff line numberDiff line change
@@ -78,8 +78,6 @@ class AvoidanceModule : public SceneModuleInterface
7878

7979
bool canTransitFailureState() override { return false; }
8080

81-
bool canTransitIdleToWaitingApprovalState() override { return true; }
82-
8381
/**
8482
* @brief update RTC status for candidate shift line.
8583
* @param candidate path.

planning/behavior_path_dynamic_avoidance_module/include/behavior_path_dynamic_avoidance_module/scene.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -345,7 +345,7 @@ class DynamicAvoidanceModule : public SceneModuleInterface
345345

346346
bool canTransitFailureState() override { return false; }
347347

348-
bool canTransitIdleToWaitingApprovalState() override { return false; }
348+
ModuleStatus setInitState() override { return ModuleStatus::IDLE; }
349349

350350
bool isLabelTargetObstacle(const uint8_t label) const;
351351
void updateTargetObjects();

planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_module.hpp

-1
Original file line numberDiff line numberDiff line change
@@ -356,7 +356,6 @@ class GoalPlannerModule : public SceneModuleInterface
356356
// If terminating it, it may switch to lane following and could generate an inappropriate path.
357357
bool canTransitSuccessState() override { return false; }
358358
bool canTransitFailureState() override { return false; }
359-
bool canTransitIdleToWaitingApprovalState() override { return true; }
360359

361360
mutable StartGoalPlannerData goal_planner_data_;
362361

planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/interface.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -126,7 +126,7 @@ class LaneChangeInterface : public SceneModuleInterface
126126

127127
bool canTransitFailureState() override;
128128

129-
bool canTransitIdleToWaitingApprovalState() override;
129+
ModuleStatus setInitState() override { return ModuleStatus::WAITING_APPROVAL; };
130130

131131
void updateDebugMarker() const;
132132

planning/behavior_path_lane_change_module/src/interface.cpp

-23
Original file line numberDiff line numberDiff line change
@@ -288,29 +288,6 @@ bool LaneChangeInterface::canTransitFailureState()
288288
return false;
289289
}
290290

291-
bool LaneChangeInterface::canTransitIdleToWaitingApprovalState()
292-
{
293-
updateDebugMarker();
294-
295-
auto log_debug_throttled = [&](std::string_view message) -> void {
296-
RCLCPP_DEBUG(getLogger(), "%s", message.data());
297-
};
298-
299-
log_debug_throttled(__func__);
300-
301-
if (!isActivated()) {
302-
if (module_type_->specialRequiredCheck()) {
303-
return true;
304-
}
305-
log_debug_throttled("Module is idling.");
306-
return false;
307-
}
308-
309-
log_debug_throttled("Can lane change safely. Executing lane change.");
310-
module_type_->toNormalState();
311-
return true;
312-
}
313-
314291
void LaneChangeInterface::updateDebugMarker() const
315292
{
316293
if (!parameters_->publish_debug_marker) {

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

+6-9
Original file line numberDiff line numberDiff line change
@@ -373,13 +373,10 @@ class SceneModuleInterface
373373
RCLCPP_DEBUG(getLogger(), "%s", message.data());
374374
};
375375
if (current_state_ == ModuleStatus::IDLE) {
376-
if (canTransitIdleToWaitingApprovalState()) {
377-
log_debug_throttled("transiting from IDLE to WAITING_APPROVAL");
378-
return ModuleStatus::WAITING_APPROVAL;
379-
}
380-
381-
log_debug_throttled("transiting from IDLE to IDLE");
382-
return ModuleStatus::IDLE;
376+
auto init_state = setInitState();
377+
RCLCPP_DEBUG(
378+
getLogger(), "transiting from IDLE to %s", magic_enum::enum_name(init_state).data());
379+
return init_state;
383380
}
384381

385382
if (current_state_ == ModuleStatus::RUNNING) {
@@ -460,9 +457,9 @@ class SceneModuleInterface
460457
virtual bool canTransitFailureState() = 0;
461458

462459
/**
463-
* @brief State transition condition IDLE -> RUNNING
460+
* @brief Explicitly set the initial state
464461
*/
465-
virtual bool canTransitIdleToWaitingApprovalState() = 0;
462+
virtual ModuleStatus setInitState() { return ModuleStatus::RUNNING; }
466463

467464
/**
468465
* @brief Get candidate path. This information is used for external judgement.

planning/behavior_path_side_shift_module/include/behavior_path_side_shift_module/scene.hpp

-2
Original file line numberDiff line numberDiff line change
@@ -75,8 +75,6 @@ class SideShiftModule : public SceneModuleInterface
7575

7676
bool canTransitFailureState() override { return false; }
7777

78-
bool canTransitIdleToWaitingApprovalState() override { return true; }
79-
8078
void initVariables();
8179

8280
// non-const methods

planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -139,7 +139,7 @@ class StartPlannerModule : public SceneModuleInterface
139139

140140
bool canTransitFailureState() override { return false; }
141141

142-
bool canTransitIdleToRunningState() override { return true; }
142+
ModuleStatus setInitState() override;
143143

144144
/**
145145
* @brief init member variables.

planning/behavior_path_start_planner_module/src/start_planner_module.cpp

+3-2
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,7 @@
2121
#include "behavior_path_start_planner_module/util.hpp"
2222
#include "motion_utils/trajectory/trajectory.hpp"
2323

24+
#include <behavior_path_planner_common/interface/scene_module_interface.hpp>
2425
#include <lanelet2_extension/utility/query.hpp>
2526
#include <lanelet2_extension/utility/utilities.hpp>
2627
#include <magic_enum.hpp>
@@ -347,9 +348,9 @@ bool StartPlannerModule::canTransitSuccessState()
347348
return hasFinishedPullOut();
348349
}
349350

350-
bool StartPlannerModule::canTransitIdleToWaitingApprovalState()
351+
ModuleStatus StartPlannerModule::setInitState()
351352
{
352-
return isActivated();
353+
return isActivated() ? ModuleStatus::RUNNING : ModuleStatus::IDLE;
353354
}
354355

355356
BehaviorModuleOutput StartPlannerModule::plan()

0 commit comments

Comments
 (0)