Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

refactor(bpp): remove virtual qualifier #5968

Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,10 @@ class LaneChangeInterface : public SceneModuleInterface

bool isExecutionReady() const override;

bool isRootLaneletToBeUpdated() const override { return current_state_ == ModuleStatus::SUCCESS; }
bool isRootLaneletToBeUpdated() const override
{
return getCurrentStatus() == ModuleStatus::SUCCESS;
}

void updateData() override;

Expand Down
4 changes: 2 additions & 2 deletions planning/behavior_path_lane_change_module/src/interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@ void LaneChangeInterface::processOnExit()

bool LaneChangeInterface::isExecutionRequested() const
{
if (current_state_ == ModuleStatus::RUNNING) {
if (getCurrentStatus() == ModuleStatus::RUNNING) {
return true;
}

Expand Down Expand Up @@ -359,7 +359,7 @@ MarkerArray LaneChangeInterface::getModuleVirtualWall()
return marker;
}

if (isWaitingApproval() || current_state_ != ModuleStatus::RUNNING) {
if (isWaitingApproval() || getCurrentStatus() != ModuleStatus::RUNNING) {
return marker;
}
const auto & start_pose = module_type_->getLaneChangePath().info.lane_changing_start;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -111,21 +111,6 @@ class SceneModuleInterface

virtual void acceptVisitor(const std::shared_ptr<SceneModuleVisitor> & visitor) const = 0;

/**
* @brief Set the current_state_ based on updateState output.
*/
virtual void updateCurrentState()
{
const auto print = [this](const auto & from, const auto & to) {
RCLCPP_DEBUG(
getLogger(), "[%s] Transit from %s to %s.", name_.c_str(), from.data(), to.data());
};

const auto & from = current_state_;
current_state_ = updateState();
print(magic_enum::enum_name(from), magic_enum::enum_name(current_state_));
}

/**
* @brief Return true if the module has request for execution (not necessarily feasible)
*/
Expand Down Expand Up @@ -159,6 +144,21 @@ class SceneModuleInterface
return isWaitingApproval() ? planWaitingApproval() : plan();
}

/**
* @brief Set the current_state_ based on updateState output.
*/
void updateCurrentState()
{
const auto print = [this](const auto & from, const auto & to) {
RCLCPP_DEBUG(
getLogger(), "[%s] Transit from %s to %s.", name_.c_str(), from.data(), to.data());
};

const auto & from = current_state_;
current_state_ = updateState();
print(magic_enum::enum_name(from), magic_enum::enum_name(current_state_));
}

/**
* @brief Called on the first time when the module goes into RUNNING.
*/
Expand Down Expand Up @@ -362,8 +362,84 @@ class SceneModuleInterface
return existApprovedRequest();
}

/**
* @brief Return SUCCESS if plan is not needed or plan is successfully finished,
* FAILURE if plan has failed, RUNNING if plan is on going.
* These condition is to be implemented in each modules.
*/
ModuleStatus updateState()
{
auto log_debug_throttled = [&](std::string_view message) -> void {
RCLCPP_WARN(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;
}

if (current_state_ == ModuleStatus::RUNNING) {
if (canTransitSuccessState()) {
log_debug_throttled("transiting from RUNNING to SUCCESS");
return ModuleStatus::SUCCESS;
}

if (canTransitFailureState()) {
log_debug_throttled("transiting from RUNNING to FAILURE");
return ModuleStatus::FAILURE;
}

if (canTransitWaitingApprovalState()) {
log_debug_throttled("transiting from RUNNING to WAITING_APPROVAL");
return ModuleStatus::WAITING_APPROVAL;
}

log_debug_throttled("transiting from RUNNING to RUNNING");
return ModuleStatus::RUNNING;
}

if (current_state_ == ModuleStatus::WAITING_APPROVAL) {
if (canTransitSuccessState()) {
log_debug_throttled("transiting from WAITING_APPROVAL to SUCCESS");
return ModuleStatus::SUCCESS;
}

if (canTransitFailureState()) {
log_debug_throttled("transiting from WAITING_APPROVAL to FAILURE");
return ModuleStatus::FAILURE;
}

if (canTransitWaitingApprovalToRunningState()) {
log_debug_throttled("transiting from WAITING_APPROVAL to RUNNING");
return ModuleStatus::RUNNING;
}

log_debug_throttled("transiting from WAITING_APPROVAL to WAITING APPROVAL");
return ModuleStatus::WAITING_APPROVAL;
}

if (current_state_ == ModuleStatus::SUCCESS) {
log_debug_throttled("already SUCCESS");
return ModuleStatus::SUCCESS;
}

if (current_state_ == ModuleStatus::FAILURE) {
log_debug_throttled("already FAILURE");
return ModuleStatus::FAILURE;
}

log_debug_throttled("already IDLE");
return ModuleStatus::IDLE;
}

std::string name_;

ModuleStatus current_state_{ModuleStatus::IDLE};

BehaviorModuleOutput previous_module_output_;

StopReason stop_reason_;
Expand Down Expand Up @@ -442,80 +518,6 @@ class SceneModuleInterface
}
}

/**
* @brief Return SUCCESS if plan is not needed or plan is successfully finished,
* FAILURE if plan has failed, RUNNING if plan is on going.
* These condition is to be implemented in each modules.
*/
virtual ModuleStatus updateState()
{
auto log_debug_throttled = [&](std::string_view message) -> void {
RCLCPP_WARN(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;
}

if (current_state_ == ModuleStatus::RUNNING) {
if (canTransitSuccessState()) {
log_debug_throttled("transiting from RUNNING to SUCCESS");
return ModuleStatus::SUCCESS;
}

if (canTransitFailureState()) {
log_debug_throttled("transiting from RUNNING to FAILURE");
return ModuleStatus::FAILURE;
}

if (canTransitWaitingApprovalState()) {
log_debug_throttled("transiting from RUNNING to WAITING_APPROVAL");
return ModuleStatus::WAITING_APPROVAL;
}

log_debug_throttled("transiting from RUNNING to RUNNING");
return ModuleStatus::RUNNING;
}

if (current_state_ == ModuleStatus::WAITING_APPROVAL) {
if (canTransitSuccessState()) {
log_debug_throttled("transiting from WAITING_APPROVAL to SUCCESS");
return ModuleStatus::SUCCESS;
}

if (canTransitFailureState()) {
log_debug_throttled("transiting from WAITING_APPROVAL to FAILURE");
return ModuleStatus::FAILURE;
}

if (canTransitWaitingApprovalToRunningState()) {
log_debug_throttled("transiting from WAITING_APPROVAL to RUNNING");
return ModuleStatus::RUNNING;
}

log_debug_throttled("transiting from WAITING_APPROVAL to WAITING APPROVAL");
return ModuleStatus::WAITING_APPROVAL;
}

if (current_state_ == ModuleStatus::SUCCESS) {
log_debug_throttled("already SUCCESS");
return ModuleStatus::SUCCESS;
}

if (current_state_ == ModuleStatus::FAILURE) {
log_debug_throttled("already FAILURE");
return ModuleStatus::FAILURE;
}

log_debug_throttled("already IDLE");
return ModuleStatus::IDLE;
}

/**
* @brief Return true if the activation command is received from the RTC interface.
* If no RTC interface is registered, return true.
Expand Down Expand Up @@ -610,8 +612,6 @@ class SceneModuleInterface
PlanResult path_candidate_;
PlanResult path_reference_;

ModuleStatus current_state_{ModuleStatus::IDLE};

std::unordered_map<std::string, std::shared_ptr<RTCInterface>> rtc_interface_ptr_map_;

std::unordered_map<std::string, std::shared_ptr<ObjectsOfInterestMarkerInterface>>
Expand Down
Loading