Skip to content

Commit

Permalink
fix(bpp): transition from IDLE to WAITING APPROVAL (autowarefoundatio…
Browse files Browse the repository at this point in the history
…n#6051)

* fix(bpp): explicitly set the initial state

Signed-off-by: Muhammad Zulfaqar Azmi <zulfaqar.azmi@tier4.jp>

* remove isWaitingApproval() from state transition

Signed-off-by: Muhammad Zulfaqar Azmi <zulfaqar.azmi@tier4.jp>

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

Co-authored-by: Fumiya Watanabe <rej55.g@gmail.com>

* explicitly set the initial state

Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp>

* remove setInitState in start_planner_module

Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp>

---------

Signed-off-by: Muhammad Zulfaqar Azmi <zulfaqar.azmi@tier4.jp>
Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp>
Co-authored-by: Fumiya Watanabe <rej55.g@gmail.com>
  • Loading branch information
2 people authored and karishma1911 committed Jun 3, 2024
1 parent 378aa5e commit a02e52b
Show file tree
Hide file tree
Showing 9 changed files with 11 additions and 41 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -78,8 +78,6 @@ class AvoidanceModule : public SceneModuleInterface

bool canTransitFailureState() override { return false; }

bool canTransitIdleToRunningState() override { return true; }

/**
* @brief update RTC status for candidate shift line.
* @param candidate path.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -345,7 +345,7 @@ class DynamicAvoidanceModule : public SceneModuleInterface

bool canTransitFailureState() override { return false; }

bool canTransitIdleToRunningState() override { return false; }
ModuleStatus setInitState() const override { return ModuleStatus::IDLE; }

bool isLabelTargetObstacle(const uint8_t label) const;
void updateTargetObjects();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -356,7 +356,6 @@ class GoalPlannerModule : public SceneModuleInterface
// If terminating it, it may switch to lane following and could generate an inappropriate path.
bool canTransitSuccessState() override { return false; }
bool canTransitFailureState() override { return false; }
bool canTransitIdleToRunningState() override { return true; }

mutable StartGoalPlannerData goal_planner_data_;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -1863,6 +1863,9 @@ void GoalPlannerModule::updateSafetyCheckTargetObjectsData(

std::pair<bool, bool> GoalPlannerModule::isSafePath() const
{
if (!thread_safe_data_.get_pull_over_path()) {
return {false, false};
}
const auto pull_over_path = thread_safe_data_.get_pull_over_path()->getCurrentPath();
const auto & current_pose = planner_data_->self_odometry->pose.pose;
const double current_velocity = std::hypot(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -126,7 +126,7 @@ class LaneChangeInterface : public SceneModuleInterface

bool canTransitFailureState() override;

bool canTransitIdleToRunningState() override;
ModuleStatus setInitState() const override { return ModuleStatus::WAITING_APPROVAL; };

void updateDebugMarker() const;

Expand Down
23 changes: 0 additions & 23 deletions planning/behavior_path_lane_change_module/src/interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -297,29 +297,6 @@ bool LaneChangeInterface::canTransitFailureState()
return false;
}

bool LaneChangeInterface::canTransitIdleToRunningState()
{
updateDebugMarker();

auto log_debug_throttled = [&](std::string_view message) -> void {
RCLCPP_DEBUG(getLogger(), "%s", message.data());
};

log_debug_throttled(__func__);

if (!isActivated() || isWaitingApproval()) {
if (module_type_->specialRequiredCheck()) {
return true;
}
log_debug_throttled("Module is idling.");
return false;
}

log_debug_throttled("Can lane change safely. Executing lane change.");
module_type_->toNormalState();
return true;
}

void LaneChangeInterface::updateDebugMarker() const
{
if (!parameters_->publish_debug_marker) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -373,13 +373,10 @@ class SceneModuleInterface
RCLCPP_DEBUG(getLogger(), "%s", message.data());
};
if (current_state_ == ModuleStatus::IDLE) {
if (canTransitIdleToRunningState()) {
log_debug_throttled("transiting from IDLE to RUNNING");
return ModuleStatus::RUNNING;
}

log_debug_throttled("transiting from IDLE to IDLE");
return ModuleStatus::IDLE;
auto init_state = setInitState();
RCLCPP_DEBUG(
getLogger(), "transiting from IDLE to %s", magic_enum::enum_name(init_state).data());
return init_state;
}

if (current_state_ == ModuleStatus::RUNNING) {
Expand Down Expand Up @@ -460,9 +457,9 @@ class SceneModuleInterface
virtual bool canTransitFailureState() = 0;

/**
* @brief State transition condition IDLE -> RUNNING
* @brief Explicitly set the initial state
*/
virtual bool canTransitIdleToRunningState() = 0;
virtual ModuleStatus setInitState() const { return ModuleStatus::RUNNING; }

/**
* @brief Get candidate path. This information is used for external judgement.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -75,8 +75,6 @@ class SideShiftModule : public SceneModuleInterface

bool canTransitFailureState() override { return false; }

bool canTransitIdleToRunningState() override { return true; }

void initVariables();

// non-const methods
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -139,8 +139,6 @@ class StartPlannerModule : public SceneModuleInterface

bool canTransitFailureState() override { return false; }

bool canTransitIdleToRunningState() override { return true; }

/**
* @brief init member variables.
*/
Expand Down

0 comments on commit a02e52b

Please sign in to comment.