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

fix(behavior_path_planner): use SUCCESS instead of IDLE when onExit #2391

Merged
merged 1 commit into from
Nov 30, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
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 @@ -31,7 +31,7 @@ struct SceneModuleStatus
bool is_requested{false};
bool is_execution_ready{false};
bool is_waiting_approval{false};
BT::NodeStatus status{BT::NodeStatus::IDLE};
BT::NodeStatus status{BT::NodeStatus::SUCCESS};
};

class SceneModuleBTNodeInterface : public BT::CoroActionNode
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -87,7 +87,7 @@ class SceneModuleInterface
clock_{node.get_clock()},
uuid_(generateUUID()),
is_waiting_approval_{false},
current_state_{BT::NodeStatus::IDLE}
current_state_{BT::NodeStatus::SUCCESS}
{
std::string module_ns;
module_ns.resize(name.size());
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2645,7 +2645,7 @@ void AvoidanceModule::onExit()
{
DEBUG_PRINT("AVOIDANCE onExit");
initVariables();
current_state_ = BT::NodeStatus::IDLE;
current_state_ = BT::NodeStatus::SUCCESS;
clearWaitingApproval();
removeRTCStatus();
steering_factor_interface_ptr_->clearSteeringFactors();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,7 @@ void LaneFollowingModule::onEntry()
void LaneFollowingModule::onExit()
{
initParam();
current_state_ = BT::NodeStatus::IDLE;
current_state_ = BT::NodeStatus::SUCCESS;
RCLCPP_DEBUG(getLogger(), "LANE_FOLLOWING onExit");
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -100,7 +100,7 @@ void PullOutModule::onExit()
clearWaitingApproval();
removeRTCStatus();
steering_factor_interface_ptr_->clearSteeringFactors();
current_state_ = BT::NodeStatus::IDLE;
current_state_ = BT::NodeStatus::SUCCESS;
RCLCPP_DEBUG(getLogger(), "PULL_OUT onExit");
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -184,7 +184,6 @@ void PullOverModule::onExit()
steering_factor_interface_ptr_->clearSteeringFactors();

// A child node must never return IDLE
// https://github.com/BehaviorTree/BehaviorTree.CPP/blob/master/include/behaviortree_cpp_v3/basic_types.h#L34
Copy link
Contributor Author

@kosuke55 kosuke55 Nov 28, 2022

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

the link is already invalid now.
it moved to https://github.com/BehaviorTree/BehaviorTree.CPP/blob/master/include/behaviortree_cpp/basic_types.h#L35, but remove it considering the maintenance cost

current_state_ = BT::NodeStatus::SUCCESS;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ void SideShiftModule::onExit()
// write me...
initVariables();

current_state_ = BT::NodeStatus::IDLE;
current_state_ = BT::NodeStatus::SUCCESS;
}

void SideShiftModule::setParameters(const SideShiftParameters & parameters)
Expand Down