Skip to content

Commit

Permalink
fix(behavior_path_planner): use SUCCESS instead of IDLE when onExit (a…
Browse files Browse the repository at this point in the history
…utowarefoundation#2391)

Signed-off-by: kosuke55 <kosuke.tnp@gmail.com>

Signed-off-by: kosuke55 <kosuke.tnp@gmail.com>
  • Loading branch information
kosuke55 authored Nov 30, 2022
1 parent 08f5eaf commit 1b77bba
Show file tree
Hide file tree
Showing 7 changed files with 6 additions and 7 deletions.
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 @@ -2647,7 +2647,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
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

0 comments on commit 1b77bba

Please sign in to comment.