Skip to content

Commit fb81f5d

Browse files
RBT22SteveMacenski
andcommitted
Pipe error codes (ros-navigation#3251)
* issue with finding key * passed up codes to bt_navigator * lint fix * updates * adding error_code_id back in * error codes names in params * bump error codes * lint * spelling * test fix * update behavior trees * cleanup * Update bt_action_server_impl.hpp * code review * lint * code review * log fix * error code for waypoint follower * clean up * remove waypoint error test, too flaky on CI * lint and code review * rough imp for waypoint changes * lint * code review * build fix * clean up * revert * space * remove * try to make github happ * stop gap * loading in param file * working tests :) * lint * fixed cmake * lint * lint * trigger build * added invalid plugin error * added test for piping up error codes * clean up * test waypoint follower * only launch what is needed * waypoint test * revert lines for robot navigator * fix test * waypoint test * switched to uint16 * clean up * code review * todo to note * lint * remove comment * Update nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server_impl.hpp Co-authored-by: Steve Macenski <[email protected]> * rename error_codes * error code for navigate to pose * error codes for navigate through poses. * error codes for navigate through poses * message update for waypoint follower * rename to error code * update node xml Co-authored-by: Joshua Wallace <josho.wallace.com> Co-authored-by: Steve Macenski <[email protected]>
1 parent 4217510 commit fb81f5d

File tree

57 files changed

+1178
-116
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

57 files changed

+1178
-116
lines changed

nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server.hpp

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -189,6 +189,13 @@ class BtActionServer
189189
*/
190190
void executeCallback();
191191

192+
/**
193+
* @brief updates the action server result to the highest priority error code posted on the
194+
* blackboard
195+
* @param result the action server result to be updated
196+
*/
197+
void populateErrorCode(typename std::shared_ptr<typename ActionT::Result> result);
198+
192199
// Action name
193200
std::string action_name_;
194201

@@ -211,6 +218,9 @@ class BtActionServer
211218
// Libraries to pull plugins (BT Nodes) from
212219
std::vector<std::string> plugin_lib_names_;
213220

221+
// Error code id names
222+
std::vector<std::string> error_code_names_;
223+
214224
// A regular, non-spinning ROS node that we can use for calls to the action client
215225
rclcpp::Node::SharedPtr client_node_;
216226

nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server_impl.hpp

Lines changed: 49 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,7 @@
2121
#include <set>
2222
#include <exception>
2323
#include <vector>
24+
#include <limits>
2425

2526
#include "nav2_msgs/action/navigate_to_pose.hpp"
2627
#include "nav2_behavior_tree/bt_action_server.hpp"
@@ -60,6 +61,24 @@ BtActionServer<ActionT>::BtActionServer(
6061
if (!node->has_parameter("default_server_timeout")) {
6162
node->declare_parameter("default_server_timeout", 20);
6263
}
64+
65+
std::vector<std::string> error_code_names = {
66+
"follow_path_error_code",
67+
"compute_path_error_code"
68+
};
69+
70+
if (!node->has_parameter("error_code_names")) {
71+
std::string error_codes_str;
72+
for (const auto & error_code : error_code_names) {
73+
error_codes_str += error_code + "\n";
74+
}
75+
RCLCPP_WARN_STREAM(
76+
logger_, "Error_code parameters were not set. Using default values of: "
77+
<< error_codes_str
78+
<< "Make sure these match your BT and there are not other sources of error codes you want "
79+
"reported to your application");
80+
node->declare_parameter("error_code_names", error_code_names);
81+
}
6382
}
6483

6584
template<class ActionT>
@@ -113,6 +132,9 @@ bool BtActionServer<ActionT>::on_configure()
113132
node->get_parameter("default_server_timeout", timeout);
114133
default_server_timeout_ = std::chrono::milliseconds(timeout);
115134

135+
// Get error code id names to grab off of the blackboard
136+
error_code_names_ = node->get_parameter("error_code_names").as_string_array();
137+
116138
// Create the class that registers our custom nodes and executes the BT
117139
bt_ = std::make_unique<nav2_behavior_tree::BehaviorTreeEngine>(plugin_lib_names_);
118140

@@ -235,6 +257,9 @@ void BtActionServer<ActionT>::executeCallback()
235257
// Give server an opportunity to populate the result message or simple give
236258
// an indication that the action is complete.
237259
auto result = std::make_shared<typename ActionT::Result>();
260+
261+
populateErrorCode(result);
262+
238263
on_completion_callback_(result, rc);
239264

240265
switch (rc) {
@@ -255,6 +280,30 @@ void BtActionServer<ActionT>::executeCallback()
255280
}
256281
}
257282

283+
template<class ActionT>
284+
void BtActionServer<ActionT>::populateErrorCode(
285+
typename std::shared_ptr<typename ActionT::Result> result)
286+
{
287+
int highest_priority_error_code = std::numeric_limits<int>::max();
288+
for (const auto & error_code : error_code_names_) {
289+
try {
290+
int current_error_code = blackboard_->get<int>(error_code);
291+
if (current_error_code != 0 && current_error_code < highest_priority_error_code) {
292+
highest_priority_error_code = current_error_code;
293+
}
294+
} catch (...) {
295+
RCLCPP_ERROR(
296+
logger_,
297+
"Failed to get error code: %s from blackboard",
298+
error_code.c_str());
299+
}
300+
}
301+
302+
if (highest_priority_error_code != std::numeric_limits<int>::max()) {
303+
result->error_code = highest_priority_error_code;
304+
}
305+
}
306+
258307
} // namespace nav2_behavior_tree
259308

260309
#endif // NAV2_BEHAVIOR_TREE__BT_ACTION_SERVER_IMPL_HPP_

nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/compute_path_through_poses_action.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -86,7 +86,7 @@ class ComputePathThroughPosesAction
8686
"Mapped name to the planner plugin type to use"),
8787
BT::OutputPort<nav_msgs::msg::Path>("path", "Path created by ComputePathThroughPoses node"),
8888
BT::OutputPort<ActionResult::_error_code_type>(
89-
"compute_path_through_poses_error_code", "The compute path through poses error code"),
89+
"error_code_id", "The compute path through poses error code"),
9090
});
9191
}
9292
};

nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/compute_path_to_pose_action.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -86,7 +86,7 @@ class ComputePathToPoseAction : public BtActionNode<nav2_msgs::action::ComputePa
8686
"Mapped name to the planner plugin type to use"),
8787
BT::OutputPort<nav_msgs::msg::Path>("path", "Path created by ComputePathToPose node"),
8888
BT::OutputPort<ActionResult::_error_code_type>(
89-
"compute_path_to_pose_error_code", "The compute path to pose error code"),
89+
"error_code_id", "The compute path to pose error code"),
9090
});
9191
}
9292
};

nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/follow_path_action.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -85,7 +85,7 @@ class FollowPathAction : public BtActionNode<nav2_msgs::action::FollowPath>
8585
BT::InputPort<std::string>("controller_id", ""),
8686
BT::InputPort<std::string>("goal_checker_id", ""),
8787
BT::OutputPort<ActionResult::_error_code_type>(
88-
"follow_path_error_code", "The follow path error code"),
88+
"error_code_id", "The follow path error code"),
8989
});
9090
}
9191
};

nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/navigate_through_poses_action.hpp

Lines changed: 21 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -30,6 +30,10 @@ namespace nav2_behavior_tree
3030
*/
3131
class NavigateThroughPosesAction : public BtActionNode<nav2_msgs::action::NavigateThroughPoses>
3232
{
33+
using Action = nav2_msgs::action::NavigateThroughPoses;
34+
using ActionResult = Action::Result;
35+
using ActionGoal = Action::Goal;
36+
3337
public:
3438
/**
3539
* @brief A constructor for nav2_behavior_tree::NavigateThroughPosesAction
@@ -47,6 +51,21 @@ class NavigateThroughPosesAction : public BtActionNode<nav2_msgs::action::Naviga
4751
*/
4852
void on_tick() override;
4953

54+
/**
55+
* @brief Function to perform some user-defined operation upon successful completion of the action
56+
*/
57+
BT::NodeStatus on_success() override;
58+
59+
/**
60+
* @brief Function to perform some user-defined operation upon abortion of the action
61+
*/
62+
BT::NodeStatus on_aborted() override;
63+
64+
/**
65+
* @brief Function to perform some user-defined operation upon cancellation of the action
66+
*/
67+
BT::NodeStatus on_cancelled() override;
68+
5069
/**
5170
* @brief Creates list of BT ports
5271
* @return BT::PortsList Containing basic ports along with node-specific ports
@@ -57,6 +76,8 @@ class NavigateThroughPosesAction : public BtActionNode<nav2_msgs::action::Naviga
5776
{
5877
BT::InputPort<geometry_msgs::msg::PoseStamped>("goals", "Destinations to plan through"),
5978
BT::InputPort<std::string>("behavior_tree", "Behavior tree to run"),
79+
BT::OutputPort<ActionResult::_error_code_type>(
80+
"error_code_id", "The navigate through poses error code"),
6081
});
6182
}
6283
};

nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/navigate_to_pose_action.hpp

Lines changed: 21 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -30,6 +30,10 @@ namespace nav2_behavior_tree
3030
*/
3131
class NavigateToPoseAction : public BtActionNode<nav2_msgs::action::NavigateToPose>
3232
{
33+
using Action = nav2_msgs::action::NavigateToPose;
34+
using ActionResult = Action::Result;
35+
using ActionGoal = Action::Goal;
36+
3337
public:
3438
/**
3539
* @brief A constructor for nav2_behavior_tree::NavigateToPoseAction
@@ -47,6 +51,21 @@ class NavigateToPoseAction : public BtActionNode<nav2_msgs::action::NavigateToPo
4751
*/
4852
void on_tick() override;
4953

54+
/**
55+
* @brief Function to perform some user-defined operation upon successful completion of the action
56+
*/
57+
BT::NodeStatus on_success() override;
58+
59+
/**
60+
* @brief Function to perform some user-defined operation upon abortion of the action
61+
*/
62+
BT::NodeStatus on_aborted() override;
63+
64+
/**
65+
* @brief Function to perform some user-defined operation upon cancellation of the action
66+
*/
67+
BT::NodeStatus on_cancelled() override;
68+
5069
/**
5170
* @brief Creates list of BT ports
5271
* @return BT::PortsList Containing basic ports along with node-specific ports
@@ -57,6 +76,8 @@ class NavigateToPoseAction : public BtActionNode<nav2_msgs::action::NavigateToPo
5776
{
5877
BT::InputPort<geometry_msgs::msg::PoseStamped>("goal", "Destination to plan to"),
5978
BT::InputPort<std::string>("behavior_tree", "Behavior tree to run"),
79+
BT::OutputPort<ActionResult::_error_code_type>(
80+
"error_code_id", "Navigate to pose error code"),
6081
});
6182
}
6283
};

nav2_behavior_tree/nav2_tree_nodes.xml

Lines changed: 5 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -77,7 +77,7 @@
7777
<input_port name="server_name">Server name</input_port>
7878
<input_port name="server_timeout">Server timeout</input_port>
7979
<output_port name="path">Path created by ComputePathToPose node</output_port>
80-
<output_port name="compute_path_to_pose_error_code">"The compute path to pose error code"</output_port>
80+
<output_port name="error_code_id">"Compute path to pose error code"</output_port>
8181
</Action>
8282

8383
<Action ID="ComputePathThroughPoses">
@@ -87,8 +87,7 @@
8787
<input_port name="server_timeout">Server timeout</input_port>
8888
<input_port name="planner_id">Mapped name to the planner plugin type to use</input_port>
8989
<output_port name="path">Path created by ComputePathToPose node</output_port>
90-
<output_port name="compute_path_through_poses_error_code">"The compute path through poses
91-
pose error code"</output_port>
90+
<output_port name="error_code_id">"Compute path through poses error code"</output_port>
9291
</Action>
9392

9493
<Action ID="RemovePassedGoals">
@@ -115,21 +114,23 @@
115114
<input_port name="goal_checker_id">Goal checker</input_port>
116115
<input_port name="server_name">Server name</input_port>
117116
<input_port name="server_timeout">Server timeout</input_port>
118-
<output_port name="follow_path_error_code">Follow Path error code</output_port>
117+
<output_port name="error_code_id">Follow Path error code</output_port>
119118
</Action>
120119

121120
<Action ID="NavigateToPose">
122121
<input_port name="goal">Goal</input_port>
123122
<input_port name="server_name">Server name</input_port>
124123
<input_port name="server_timeout">Server timeout</input_port>
125124
<input_port name="behavior_tree">Behavior tree to run</input_port>
125+
<output_port name="error_code_id">Navigate to pose error code</output_port>
126126
</Action>
127127

128128
<Action ID="NavigateThroughPoses">
129129
<input_port name="goals">Goals</input_port>
130130
<input_port name="server_name">Server name</input_port>
131131
<input_port name="server_timeout">Server timeout</input_port>
132132
<input_port name="behavior_tree">Behavior tree to run</input_port>
133+
<output_port name="error_code_id">Navigate through poses error code</output_port>
133134
</Action>
134135

135136
<Action ID="ReinitializeGlobalLocalization">

nav2_behavior_tree/plugins/action/compute_path_through_poses_action.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -42,15 +42,15 @@ BT::NodeStatus ComputePathThroughPosesAction::on_success()
4242
{
4343
setOutput("path", result_.result->path);
4444
// Set empty error code, action was successful
45-
setOutput("compute_path_through_poses_error_code", ActionGoal::NONE);
45+
setOutput("error_code_id", ActionGoal::NONE);
4646
return BT::NodeStatus::SUCCESS;
4747
}
4848

4949
BT::NodeStatus ComputePathThroughPosesAction::on_aborted()
5050
{
5151
nav_msgs::msg::Path empty_path;
5252
setOutput("path", empty_path);
53-
setOutput("compute_path_through_poses_error_code", result_.result->error_code);
53+
setOutput("error_code_id", result_.result->error_code);
5454
return BT::NodeStatus::FAILURE;
5555
}
5656

@@ -59,7 +59,7 @@ BT::NodeStatus ComputePathThroughPosesAction::on_cancelled()
5959
nav_msgs::msg::Path empty_path;
6060
setOutput("path", empty_path);
6161
// Set empty error code, action was cancelled
62-
setOutput("compute_path_through_poses_error_code", ActionGoal::NONE);
62+
setOutput("error_code_id", ActionGoal::NONE);
6363
return BT::NodeStatus::SUCCESS;
6464
}
6565

nav2_behavior_tree/plugins/action/compute_path_to_pose_action.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -41,15 +41,15 @@ BT::NodeStatus ComputePathToPoseAction::on_success()
4141
{
4242
setOutput("path", result_.result->path);
4343
// Set empty error code, action was successful
44-
setOutput("compute_path_to_pose_error_code", ActionGoal::NONE);
44+
setOutput("error_code_id", ActionGoal::NONE);
4545
return BT::NodeStatus::SUCCESS;
4646
}
4747

4848
BT::NodeStatus ComputePathToPoseAction::on_aborted()
4949
{
5050
nav_msgs::msg::Path empty_path;
5151
setOutput("path", empty_path);
52-
setOutput("compute_path_to_pose_error_code", result_.result->error_code);
52+
setOutput("error_code_id", result_.result->error_code);
5353
return BT::NodeStatus::FAILURE;
5454
}
5555

@@ -58,7 +58,7 @@ BT::NodeStatus ComputePathToPoseAction::on_cancelled()
5858
nav_msgs::msg::Path empty_path;
5959
setOutput("path", empty_path);
6060
// Set empty error code, action was cancelled
61-
setOutput("compute_path_to_pose_error_code", ActionGoal::NONE);
61+
setOutput("error_code_id", ActionGoal::NONE);
6262
return BT::NodeStatus::SUCCESS;
6363
}
6464

0 commit comments

Comments
 (0)