-
Notifications
You must be signed in to change notification settings - Fork 1.8k
Description
Description:
I’m experiencing an issue with the PersistentSequence BT node in this PR #5247. The behavior of the node is not as expected, and I’m observing an incorrect value for current_child_idx. Specifically, when logging the current_child_idx value, it prints out a garbage value (e.g., -1285962554), which causes a segmentation fault later in the execution.
Here is the relevant portion of my code where I added logging:
BT::NodeStatus PersistentSequenceNode::tick()
{
auto node = this->config().blackboard->get<rclcpp::Node::SharedPtr>("node");
const int children_count = children_nodes_.size();
int current_child_idx;
getInput("current_child_idx", current_child_idx);
RCLCPP_INFO(node->get_logger(), "Child node count: %d", children_count);
RCLCPP_INFO(node->get_logger(), "Current child idx: %d", current_child_idx);
setStatus(BT::NodeStatus::RUNNING);
while (current_child_idx < children_count) {
TreeNode * current_child_node = children_nodes_[current_child_idx];
const BT::NodeStatus child_status = current_child_node->executeTick();
switch (child_status) {
case BT::NodeStatus::RUNNING:
return child_status;
case BT::NodeStatus::FAILURE:
// Reset on failure
resetChildren();
current_child_idx = 0;
setOutput("current_child_idx", 0);
return child_status;
case BT::NodeStatus::SUCCESS:
case BT::NodeStatus::SKIPPED:
// Skip the child node
current_child_idx++;
setOutput("current_child_idx", current_child_idx);
break;
case BT::NodeStatus::IDLE:
throw std::runtime_error("A child node must never return IDLE");
} // end switch
} // end while loop
// The entire while loop completed. This means that all the children returned SUCCESS.
if (current_child_idx >= children_count) {
resetChildren();
setOutput("current_child_idx", 0);
}
return BT::NodeStatus::SUCCESS;
}
Log Output:
[component_container_isolated-9] [INFO] [1759722284.935824768] [bt_navigator]: Begin navigating from current location (7.18, 7.87) to (12.73, 6.26)
[component_container_isolated-9] [INFO] [1759722284.936074266] [bt_navigator_navigate_to_pose_rclcpp_node]: Child node count: 4
[component_container_isolated-9] [INFO] [1759722284.936114956] [bt_navigator_navigate_to_pose_rclcpp_node]: Current child idx: -1285962554
[component_container_isolated-9] Magick: abort due to signal 11 (SIGSEGV) "Segmentation Fault"...
[ERROR] [component_container_isolated-9]: process has died [pid 82155, exit code -6, cmd '/home/server/ros2_kilted/install/rclcpp_components/lib/rclcpp_components/component_container_isolated --ros-args --log-level info --ros-args -r __node:=nav2_container -r __ns:=/ --params-file /tmp/launch_params_dgawt2_f --params-file /tmp/launch_params_h1bq_k31 -r /tf:=tf -r /tf_static:=tf_static'].
Issue:
It seems that the current_child_idx value is not properly initialized when the PersistentSequence node is first ticked. I suspect that it is being set to a garbage value, which leads to the observed issue.
I’ve confirmed this by printing out the value of current_child_idx during execution, and it shows an invalid value (like -1285962554). This behavior causes a segmentation fault later in the execution, possibly when attempting to access an invalid index in the children_nodes_ vector.
Here's my Behavior Tree (BT) XML:
<?xml version="1.0" encoding="UTF-8"?>
<root BTCPP_format="4"
main_tree_to_execute="MainTree">
<BehaviorTree ID="MainTree">
<PauseResumeController pause_service_name="/pause"
resume_service_name="/resume">
<PersistentSequence>
<ControllerSelector topic_name="controller_selector"
default_controller="FollowPath"
selected_controller="{selected_controller}"/>
<PlannerSelector topic_name="planner_selector"
default_planner="GridBased"
selected_planner="{selected_planner}"/>
<GoalUpdatedController>
<ComputePathToPose goal="{goal}"
planner_id="{selected_planner}"
path="{path}"
error_code_id="{compute_path_error_code}"
error_msg="{compute_path_error_msg}"/>
</GoalUpdatedController>
<FollowPath controller_id="{selected_controller}"
path="{path}"
error_code_id="{follow_path_error_code}"
error_msg="{follow_path_error_msg}"/>
</PersistentSequence>
</PauseResumeController>
</BehaviorTree>
</root>
What I suspect:
-
Uninitialized variable: The current_child_idx is not being properly initialized before use. It might be left in an uninitialized state when the first tick occurs.
-
Behavior Tree Configuration: There may be an issue with how the PersistentSequence node is set up in the BT XML.
Questions:
- Am I using the PersistentSequence node incorrectly, or is this behavior likely a bug?
- Should I manually set an initial value for current_child_idx to avoid it containing a garbage value?