Skip to content
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 @@ -79,6 +79,11 @@ class ComputeAndTrackRouteAction : public BtActionNode<nav2_msgs::action::Comput
void on_wait_for_result(
std::shared_ptr<const Action::Feedback> feedback) override;

/**
* @brief Function to set all feedbacks and output ports to be null values
*/
void resetFeedbackAndOutputPorts();

/**
* @brief Creates list of BT ports
* @return BT::PortsList Containing basic ports along with node-specific ports
Expand All @@ -99,14 +104,36 @@ class ComputeAndTrackRouteAction : public BtActionNode<nav2_msgs::action::Comput
"Whether to use the start pose or the robot's current pose"),
BT::InputPort<bool>(
"use_poses", false, "Whether to use poses or IDs for start and goal"),
BT::OutputPort<builtin_interfaces::msg::Duration>("execution_duration",
BT::OutputPort<builtin_interfaces::msg::Duration>(
"execution_duration",
"Time taken to compute and track route"),
BT::OutputPort<ActionResult::_error_code_type>(
"error_code_id", "The compute route error code"),
BT::OutputPort<std::string>(
"error_msg", "The compute route error msg"),
BT::OutputPort<uint16_t>(
"last_node_id",
"ID of the previous node"),
BT::OutputPort<uint16_t>(
"next_node_id",
"ID of the next node"),
BT::OutputPort<uint16_t>(
"current_edge_id",
"ID of current edge"),
BT::OutputPort<nav2_msgs::msg::Route>(
"route",
"List of RouteNodes to go from start to end"),
BT::OutputPort<nav_msgs::msg::Path>(
"path",
"Path created by ComputeAndTrackRoute node"),
BT::OutputPort<bool>(
"rerouted",
"Whether the plan has rerouted"),
});
}

protected:
Action::Feedback feedback_;
};

} // namespace nav2_behavior_tree
Expand Down
6 changes: 6 additions & 0 deletions nav2_behavior_tree/nav2_tree_nodes.xml
Original file line number Diff line number Diff line change
Expand Up @@ -135,6 +135,12 @@
<output_port name="execution_time">Duration to compute route</output_port>
<output_port name="error_code_id">"Compute route to pose error code"</output_port>
<output_port name="error_msg">"Compute route to pose error message"</output_port>
<output_port name="last_node_id">"ID of the previous node"</output_port>
<output_port name="next_node_id">"ID of the next node"</output_port>
<output_port name="current_edge_id">"ID of the current edge"</output_port>
<output_port name="route">"List of RouteNodes to go from start to end"</output_port>
<output_port name="path">"Path created by ComputeAndTrackRoute node"</output_port>
<output_port name="rerouted">"Whether the plan has rerouted"</output_port>
</Action>

<Action ID="RemovePassedGoals">
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,14 @@
const BT::NodeConfiguration & conf)
: BtActionNode<Action>(xml_tag_name, action_name, conf)
{
nav_msgs::msg::Path empty_path;
nav2_msgs::msg::Route empty_route;
feedback_.last_node_id = 0;
feedback_.next_node_id = 0;
feedback_.current_edge_id = 0;
feedback_.route = empty_route;
feedback_.path = empty_path;
feedback_.rerouted = false;
}

void ComputeAndTrackRouteAction::on_tick()
Expand All @@ -52,6 +60,7 @@

BT::NodeStatus ComputeAndTrackRouteAction::on_success()
{
resetFeedbackAndOutputPorts();
setOutput("execution_duration", result_.result->execution_duration);
setOutput("error_code_id", ActionResult::NONE);
setOutput("error_msg", "");
Expand All @@ -60,6 +69,7 @@

BT::NodeStatus ComputeAndTrackRouteAction::on_aborted()
{
resetFeedbackAndOutputPorts();

Check warning on line 72 in nav2_behavior_tree/plugins/action/compute_and_track_route_action.cpp

View check run for this annotation

Codecov / codecov/patch

nav2_behavior_tree/plugins/action/compute_and_track_route_action.cpp#L72

Added line #L72 was not covered by tests
setOutput("execution_duration", builtin_interfaces::msg::Duration());
setOutput("error_code_id", result_.result->error_code);
setOutput("error_msg", result_.result->error_msg);
Expand All @@ -68,6 +78,7 @@

BT::NodeStatus ComputeAndTrackRouteAction::on_cancelled()
{
resetFeedbackAndOutputPorts();

Check warning on line 81 in nav2_behavior_tree/plugins/action/compute_and_track_route_action.cpp

View check run for this annotation

Codecov / codecov/patch

nav2_behavior_tree/plugins/action/compute_and_track_route_action.cpp#L81

Added line #L81 was not covered by tests
// Set empty error code, action was cancelled
setOutput("execution_duration", builtin_interfaces::msg::Duration());
setOutput("error_code_id", ActionResult::NONE);
Expand All @@ -82,7 +93,7 @@
}

void ComputeAndTrackRouteAction::on_wait_for_result(
std::shared_ptr<const Action::Feedback>/*feedback*/)
std::shared_ptr<const Action::Feedback> feedback)
{
// Check for request updates to the goal
bool use_poses = false, use_start = false;
Expand Down Expand Up @@ -129,6 +140,34 @@
if (goal_updated_) {
on_tick();
}

if (feedback) {
feedback_ = *feedback;
setOutput("last_node_id", feedback_.last_node_id);
setOutput("next_node_id", feedback_.next_node_id);
setOutput("current_edge_id", feedback_.current_edge_id);
setOutput("route", feedback_.route);
setOutput("path", feedback_.path);
setOutput("rerouted", feedback_.rerouted);

Check warning on line 151 in nav2_behavior_tree/plugins/action/compute_and_track_route_action.cpp

View check run for this annotation

Codecov / codecov/patch

nav2_behavior_tree/plugins/action/compute_and_track_route_action.cpp#L145-L151

Added lines #L145 - L151 were not covered by tests
}
}

void ComputeAndTrackRouteAction::resetFeedbackAndOutputPorts()
{
nav_msgs::msg::Path empty_path;
nav2_msgs::msg::Route empty_route;
feedback_.last_node_id = 0;
feedback_.next_node_id = 0;
feedback_.current_edge_id = 0;
feedback_.route = empty_route;
feedback_.path = empty_path;
feedback_.rerouted = false;
setOutput("last_node_id", feedback_.last_node_id);
setOutput("next_node_id", feedback_.next_node_id);
setOutput("current_edge_id", feedback_.current_edge_id);
setOutput("route", feedback_.route);
setOutput("path", feedback_.path);
setOutput("rerouted", feedback_.rerouted);
}

} // namespace nav2_behavior_tree
Expand Down
Loading