Skip to content

Commit

Permalink
explicitly set the initial state
Browse files Browse the repository at this point in the history
Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp>
  • Loading branch information
zulfaqar-azmi-t4 committed Jan 25, 2024
1 parent 9ec5b80 commit e4d2748
Show file tree
Hide file tree
Showing 9 changed files with 12 additions and 42 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 canTransitIdleToWaitingApprovalState() 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 canTransitIdleToWaitingApprovalState() override { return false; }
ModuleStatus setInitState() 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 canTransitIdleToWaitingApprovalState() override { return true; }

mutable StartGoalPlannerData goal_planner_data_;

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 canTransitIdleToWaitingApprovalState() override;
ModuleStatus setInitState() override { return ModuleStatus::WAITING_APPROVAL; };

void setObjectDebugVisualization() 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 @@ -289,29 +289,6 @@ bool LaneChangeInterface::canTransitFailureState()
return false;
}

bool LaneChangeInterface::canTransitIdleToWaitingApprovalState()
{
setObjectDebugVisualization();

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

log_debug_throttled(__func__);

if (!isActivated()) {
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::setObjectDebugVisualization() const
{
debug_marker_.markers.clear();
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 (canTransitIdleToWaitingApprovalState()) {
log_debug_throttled("transiting from IDLE to WAITING_APPROVAL");
return ModuleStatus::WAITING_APPROVAL;
}

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 canTransitIdleToWaitingApprovalState() = 0;
virtual ModuleStatus setInitState() { 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 canTransitIdleToWaitingApprovalState() override { return true; }

void initVariables();

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

bool canTransitFailureState() override { return false; }

bool canTransitIdleToWaitingApprovalState() override;
ModuleStatus setInitState() override;

/**
* @brief init member variables.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
#include "behavior_path_start_planner_module/util.hpp"
#include "motion_utils/trajectory/trajectory.hpp"

#include <behavior_path_planner_common/interface/scene_module_interface.hpp>
#include <lanelet2_extension/utility/query.hpp>
#include <lanelet2_extension/utility/utilities.hpp>
#include <magic_enum.hpp>
Expand Down Expand Up @@ -347,9 +348,9 @@ bool StartPlannerModule::canTransitSuccessState()
return hasFinishedPullOut();
}

bool StartPlannerModule::canTransitIdleToWaitingApprovalState()
ModuleStatus StartPlannerModule::setInitState()
{
return isActivated();
return isActivated() ? ModuleStatus::RUNNING : ModuleStatus::IDLE;
}

BehaviorModuleOutput StartPlannerModule::plan()
Expand Down

0 comments on commit e4d2748

Please sign in to comment.