Skip to content

Commit

Permalink
WIP: Make BT nodes have configurable wait times. (ros-navigation#3960)
Browse files Browse the repository at this point in the history
* Make BT nodes have configurable wait times.

Previous solution provided hardcoded 1s value.
Right now the value can be configured for BT
Action, Cancel and Service nodes.

[ros-navigation#3920]

Signed-off-by: Adam Galecki <[email protected]>

* Make BT nodes have configurable wait times.

Previous solution provided hardcoded 1s value.
Right now the value can be configured for BT
Action, Cancel and Service nodes.

[ros-navigation#3920]

Signed-off-by: Adam Galecki <[email protected]>

* Fix typos, linting errors and value type from float to int

* Fix extra underscores

* Fix extra underscore

* Update unit tests with blackboard parameter

Signed-off-by: Adam Galecki <[email protected]>

* Fix formatting errors

Signed-off-by: Adam Galecki <[email protected]>

* Update system tests to match new parameter

Signed-off-by: Adam Galecki <[email protected]>

---------

Signed-off-by: Adam Galecki <[email protected]>
  • Loading branch information
embeddedadam authored and christophfroehlich committed Jun 8, 2024
1 parent cf3dd55 commit 52f0ea5
Show file tree
Hide file tree
Showing 30 changed files with 168 additions and 14 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -61,6 +61,8 @@ class BtActionNode : public BT::ActionNodeBase
server_timeout_ =
config().blackboard->template get<std::chrono::milliseconds>("server_timeout");
getInput<std::chrono::milliseconds>("server_timeout", server_timeout_);
wait_for_service_timeout_ =
config().blackboard->template get<std::chrono::milliseconds>("wait_for_service_timeout");

// Initialize the input and output messages
goal_ = typename ActionT::Goal();
Expand Down Expand Up @@ -93,7 +95,7 @@ class BtActionNode : public BT::ActionNodeBase

// Make sure the server is actually there before continuing
RCLCPP_DEBUG(node_->get_logger(), "Waiting for \"%s\" action server", action_name.c_str());
if (!action_client_->wait_for_action_server(1s)) {
if (!action_client_->wait_for_action_server(wait_for_service_timeout_)) {
RCLCPP_ERROR(
node_->get_logger(), "\"%s\" action server not available after waiting for 1 s",
action_name.c_str());
Expand Down Expand Up @@ -459,6 +461,9 @@ class BtActionNode : public BT::ActionNodeBase
// The timeout value for BT loop execution
std::chrono::milliseconds bt_loop_duration_;

// The timeout value for waiting for a service to response
std::chrono::milliseconds wait_for_service_timeout_;

// To track the action server acknowledgement when a new goal is sent
std::shared_ptr<std::shared_future<typename rclcpp_action::ClientGoalHandle<ActionT>::SharedPtr>>
future_goal_handle_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -232,6 +232,9 @@ class BtActionServer
// Default timeout value while waiting for response from a server
std::chrono::milliseconds default_server_timeout_;

// The timeout value for waiting for a service to response
std::chrono::milliseconds wait_for_service_timeout_;

// User-provided callbacks
OnGoalReceivedCallback on_goal_received_callback_;
OnLoopCallback on_loop_callback_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -107,11 +107,15 @@ bool BtActionServer<ActionT>::on_configure()
action_name_, std::bind(&BtActionServer<ActionT>::executeCallback, this));

// Get parameters for BT timeouts
int timeout;
node->get_parameter("bt_loop_duration", timeout);
bt_loop_duration_ = std::chrono::milliseconds(timeout);
node->get_parameter("default_server_timeout", timeout);
default_server_timeout_ = std::chrono::milliseconds(timeout);
int bt_loop_duration;
node->get_parameter("bt_loop_duration", bt_loop_duration);
bt_loop_duration_ = std::chrono::milliseconds(bt_loop_duration);
int default_server_timeout;
node->get_parameter("default_server_timeout", default_server_timeout);
default_server_timeout_ = std::chrono::milliseconds(default_server_timeout);
int wait_for_service_timeout;
node->get_parameter("wait_for_service_timeout", wait_for_service_timeout);
wait_for_service_timeout_ = std::chrono::milliseconds(wait_for_service_timeout);

// Create the class that registers our custom nodes and executes the BT
bt_ = std::make_unique<nav2_behavior_tree::BehaviorTreeEngine>(plugin_lib_names_);
Expand All @@ -123,6 +127,9 @@ bool BtActionServer<ActionT>::on_configure()
blackboard_->set<rclcpp::Node::SharedPtr>("node", client_node_); // NOLINT
blackboard_->set<std::chrono::milliseconds>("server_timeout", default_server_timeout_); // NOLINT
blackboard_->set<std::chrono::milliseconds>("bt_loop_duration", bt_loop_duration_); // NOLINT
blackboard_->set<std::chrono::milliseconds>(
"wait_for_service_timeout",
wait_for_service_timeout_);

return true;
}
Expand Down Expand Up @@ -190,6 +197,9 @@ bool BtActionServer<ActionT>::loadBehaviorTree(const std::string & bt_xml_filena
blackboard->set<rclcpp::Node::SharedPtr>("node", client_node_);
blackboard->set<std::chrono::milliseconds>("server_timeout", default_server_timeout_);
blackboard->set<std::chrono::milliseconds>("bt_loop_duration", bt_loop_duration_);
blackboard->set<std::chrono::milliseconds>(
"wait_for_service_timeout",
wait_for_service_timeout_);
}
} catch (const std::exception & e) {
RCLCPP_ERROR(logger_, "Exception when loading BT: %s", e.what());
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -59,6 +59,8 @@ class BtCancelActionNode : public BT::ActionNodeBase
server_timeout_ =
config().blackboard->template get<std::chrono::milliseconds>("server_timeout");
getInput<std::chrono::milliseconds>("server_timeout", server_timeout_);
wait_for_service_timeout_ =
config().blackboard->template get<std::chrono::milliseconds>("wait_for_service_timeout");

std::string remapped_action_name;
if (getInput("server_name", remapped_action_name)) {
Expand Down Expand Up @@ -89,7 +91,7 @@ class BtCancelActionNode : public BT::ActionNodeBase

// Make sure the server is actually there before continuing
RCLCPP_DEBUG(node_->get_logger(), "Waiting for \"%s\" action server", action_name.c_str());
if (!action_client_->wait_for_action_server(1s)) {
if (!action_client_->wait_for_action_server(wait_for_service_timeout_)) {
RCLCPP_ERROR(
node_->get_logger(), "\"%s\" action server not available after waiting for 1 s",
action_name.c_str());
Expand Down Expand Up @@ -168,6 +170,8 @@ class BtCancelActionNode : public BT::ActionNodeBase
// The timeout value while waiting for response from a server when a
// new action goal is canceled
std::chrono::milliseconds server_timeout_;
// The timeout value for waiting for a service to response
std::chrono::milliseconds wait_for_service_timeout_;
};

} // namespace nav2_behavior_tree
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -62,6 +62,8 @@ class BtServiceNode : public BT::ActionNodeBase
server_timeout_ =
config().blackboard->template get<std::chrono::milliseconds>("server_timeout");
getInput<std::chrono::milliseconds>("server_timeout", server_timeout_);
wait_for_service_timeout_ =
config().blackboard->template get<std::chrono::milliseconds>("wait_for_service_timeout");

// Now that we have node_ to use, create the service client for this BT service
getInput("service_name", service_name_);
Expand All @@ -77,7 +79,7 @@ class BtServiceNode : public BT::ActionNodeBase
RCLCPP_DEBUG(
node_->get_logger(), "Waiting for \"%s\" service",
service_name_.c_str());
if (!service_client_->wait_for_service(1s)) {
if (!service_client_->wait_for_service(wait_for_service_timeout_)) {
RCLCPP_ERROR(
node_->get_logger(), "\"%s\" service server not available after waiting for 1 s",
service_node_name.c_str());
Expand Down Expand Up @@ -249,6 +251,9 @@ class BtServiceNode : public BT::ActionNodeBase
// The timeout value for BT loop execution
std::chrono::milliseconds bt_loop_duration_;

// The timeout value for waiting for a service to response
std::chrono::milliseconds wait_for_service_timeout_;

// To track the server response when a new request is sent
std::shared_future<typename ServiceT::Response::SharedPtr> future_result_;
bool request_sent_{false};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -68,6 +68,9 @@ class AssistedTeleopActionTestFixture : public ::testing::Test
config_->blackboard->set<std::chrono::milliseconds>(
"bt_loop_duration",
std::chrono::milliseconds(10));
config_->blackboard->set<std::chrono::milliseconds>(
"wait_for_service_timeout",
std::chrono::milliseconds(1000));
config_->blackboard->set<bool>("initial_pose_received", false);
config_->blackboard->set<int>("number_recoveries", 0);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -65,6 +65,9 @@ class CancelAssistedTeleopActionTestFixture : public ::testing::Test
config_->blackboard->set<std::chrono::milliseconds>(
"bt_loop_duration",
std::chrono::milliseconds(10));
config_->blackboard->set<std::chrono::milliseconds>(
"wait_for_service_timeout",
std::chrono::milliseconds(1000));
client_ = rclcpp_action::create_client<nav2_msgs::action::AssistedTeleop>(
node_, "assisted_teleop");

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -68,6 +68,9 @@ class BackUpActionTestFixture : public ::testing::Test
config_->blackboard->set<std::chrono::milliseconds>(
"bt_loop_duration",
std::chrono::milliseconds(10));
config_->blackboard->set<std::chrono::milliseconds>(
"wait_for_service_timeout",
std::chrono::milliseconds(1000));
config_->blackboard->set<bool>("initial_pose_received", false);
config_->blackboard->set<int>("number_recoveries", 0);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -64,6 +64,9 @@ class CancelBackUpActionTestFixture : public ::testing::Test
config_->blackboard->set<std::chrono::milliseconds>(
"bt_loop_duration",
std::chrono::milliseconds(10));
config_->blackboard->set<std::chrono::milliseconds>(
"wait_for_service_timeout",
std::chrono::milliseconds(1000));
client_ = rclcpp_action::create_client<nav2_msgs::action::BackUp>(
node_, "back_up");

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -173,6 +173,7 @@ class BTActionNodeTestFixture : public ::testing::Test
config_->blackboard->set<rclcpp::Node::SharedPtr>("node", node_);
config_->blackboard->set<std::chrono::milliseconds>("server_timeout", 20ms);
config_->blackboard->set<std::chrono::milliseconds>("bt_loop_duration", 10ms);
config_->blackboard->set<std::chrono::milliseconds>("wait_for_service_timeout", 1000ms);
config_->blackboard->set<bool>("initial_pose_received", false);
config_->blackboard->set<bool>("on_cancelled_triggered", false);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,9 @@ class ClearEntireCostmapServiceTestFixture : public ::testing::Test
config_->blackboard->set<std::chrono::milliseconds>(
"bt_loop_duration",
std::chrono::milliseconds(10));
config_->blackboard->set<std::chrono::milliseconds>(
"wait_for_service_timeout",
std::chrono::milliseconds(1000));
config_->blackboard->set<bool>("initial_pose_received", false);
config_->blackboard->set<int>("number_recoveries", 0);

Expand Down Expand Up @@ -139,6 +142,9 @@ class ClearCostmapExceptRegionServiceTestFixture : public ::testing::Test
config_->blackboard->set<std::chrono::milliseconds>(
"bt_loop_duration",
std::chrono::milliseconds(10));
config_->blackboard->set<std::chrono::milliseconds>(
"wait_for_service_timeout",
std::chrono::milliseconds(1000));
config_->blackboard->set<bool>("initial_pose_received", false);
config_->blackboard->set<int>("number_recoveries", 0);

Expand Down Expand Up @@ -231,6 +237,9 @@ class ClearCostmapAroundRobotServiceTestFixture : public ::testing::Test
config_->blackboard->set<std::chrono::milliseconds>(
"bt_loop_duration",
std::chrono::milliseconds(10));
config_->blackboard->set<std::chrono::milliseconds>(
"wait_for_service_timeout",
std::chrono::milliseconds(1000));
config_->blackboard->set<bool>("initial_pose_received", false);
config_->blackboard->set<int>("number_recoveries", 0);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -76,6 +76,9 @@ class ComputePathThroughPosesActionTestFixture : public ::testing::Test
config_->blackboard->set<std::chrono::milliseconds>(
"bt_loop_duration",
std::chrono::milliseconds(10));
config_->blackboard->set<std::chrono::milliseconds>(
"wait_for_service_timeout",
std::chrono::milliseconds(1000));
config_->blackboard->set<bool>("initial_pose_received", false);

BT::NodeBuilder builder =
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -74,6 +74,9 @@ class ComputePathToPoseActionTestFixture : public ::testing::Test
config_->blackboard->set<std::chrono::milliseconds>(
"bt_loop_duration",
std::chrono::milliseconds(10));
config_->blackboard->set<std::chrono::milliseconds>(
"wait_for_service_timeout",
std::chrono::milliseconds(1000));
config_->blackboard->set<bool>("initial_pose_received", false);

BT::NodeBuilder builder =
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -64,6 +64,9 @@ class CancelControllerActionTestFixture : public ::testing::Test
config_->blackboard->set<std::chrono::milliseconds>(
"bt_loop_duration",
std::chrono::milliseconds(10));
config_->blackboard->set<std::chrono::milliseconds>(
"wait_for_service_timeout",
std::chrono::milliseconds(1000));
client_ = rclcpp_action::create_client<nav2_msgs::action::FollowPath>(
node_, "follow_path");

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -69,6 +69,9 @@ class DriveOnHeadingActionTestFixture : public ::testing::Test
config_->blackboard->set<std::chrono::milliseconds>(
"bt_loop_duration",
std::chrono::milliseconds(10));
config_->blackboard->set<std::chrono::milliseconds>(
"wait_for_service_timeout",
std::chrono::milliseconds(1000));
config_->blackboard->set<bool>("initial_pose_received", false);

BT::NodeBuilder builder =
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -65,6 +65,9 @@ class CancelDriveOnHeadingTestFixture : public ::testing::Test
config_->blackboard->set<std::chrono::milliseconds>(
"bt_loop_duration",
std::chrono::milliseconds(10));
config_->blackboard->set<std::chrono::milliseconds>(
"wait_for_service_timeout",
std::chrono::milliseconds(1000));
client_ = rclcpp_action::create_client<nav2_msgs::action::DriveOnHeading>(
node_, "drive_on_heading_cancel");

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -67,6 +67,9 @@ class FollowPathActionTestFixture : public ::testing::Test
config_->blackboard->set<std::chrono::milliseconds>(
"bt_loop_duration",
std::chrono::milliseconds(10));
config_->blackboard->set<std::chrono::milliseconds>(
"wait_for_service_timeout",
std::chrono::milliseconds(1000));
config_->blackboard->set<bool>("initial_pose_received", false);

BT::NodeBuilder builder =
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -70,6 +70,9 @@ class NavigateThroughPosesActionTestFixture : public ::testing::Test
config_->blackboard->set<std::chrono::milliseconds>(
"bt_loop_duration",
std::chrono::milliseconds(10));
config_->blackboard->set<std::chrono::milliseconds>(
"wait_for_service_timeout",
std::chrono::milliseconds(1000));
config_->blackboard->set<bool>("initial_pose_received", false);
std::vector<geometry_msgs::msg::PoseStamped> poses;
config_->blackboard->set<std::vector<geometry_msgs::msg::PoseStamped>>(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -68,6 +68,9 @@ class NavigateToPoseActionTestFixture : public ::testing::Test
config_->blackboard->set<std::chrono::milliseconds>(
"bt_loop_duration",
std::chrono::milliseconds(10));
config_->blackboard->set<std::chrono::milliseconds>(
"wait_for_service_timeout",
std::chrono::milliseconds(1000));
config_->blackboard->set<bool>("initial_pose_received", false);

BT::NodeBuilder builder =
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,9 @@ class ReinitializeGlobalLocalizationServiceTestFixture : public ::testing::Test
config_->blackboard->set<std::chrono::milliseconds>(
"bt_loop_duration",
std::chrono::milliseconds(10));
config_->blackboard->set<std::chrono::milliseconds>(
"wait_for_service_timeout",
std::chrono::milliseconds(1000));
config_->blackboard->set<bool>("initial_pose_received", false);

factory_->registerNodeType<nav2_behavior_tree::ReinitializeGlobalLocalizationService>(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -67,6 +67,9 @@ class SmoothPathActionTestFixture : public ::testing::Test
config_->blackboard->set<std::chrono::milliseconds>(
"bt_loop_duration",
std::chrono::milliseconds(10));
config_->blackboard->set<std::chrono::milliseconds>(
"wait_for_service_timeout",
std::chrono::milliseconds(1000));
config_->blackboard->set<bool>("initial_pose_received", false);

BT::NodeBuilder builder =
Expand Down
3 changes: 3 additions & 0 deletions nav2_behavior_tree/test/plugins/action/test_spin_action.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,6 +68,9 @@ class SpinActionTestFixture : public ::testing::Test
config_->blackboard->set<std::chrono::milliseconds>(
"bt_loop_duration",
std::chrono::milliseconds(10));
config_->blackboard->set<std::chrono::milliseconds>(
"wait_for_service_timeout",
std::chrono::milliseconds(1000));
config_->blackboard->set<bool>("initial_pose_received", false);
config_->blackboard->set<int>("number_recoveries", 0);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -64,6 +64,9 @@ class CancelSpinActionTestFixture : public ::testing::Test
config_->blackboard->set<std::chrono::milliseconds>(
"bt_loop_duration",
std::chrono::milliseconds(10));
config_->blackboard->set<std::chrono::milliseconds>(
"wait_for_service_timeout",
std::chrono::milliseconds(1000));
client_ = rclcpp_action::create_client<nav2_msgs::action::Spin>(
node_, "spin");

Expand Down
3 changes: 3 additions & 0 deletions nav2_behavior_tree/test/plugins/action/test_wait_action.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,6 +59,9 @@ class WaitActionTestFixture : public ::testing::Test
config_->blackboard->set<std::chrono::milliseconds>(
"bt_loop_duration",
std::chrono::milliseconds(10));
config_->blackboard->set<std::chrono::milliseconds>(
"wait_for_service_timeout",
std::chrono::milliseconds(1000));
config_->blackboard->set<bool>("initial_pose_received", false);
config_->blackboard->set<int>("number_recoveries", 0);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -64,6 +64,9 @@ class CancelWaitActionTestFixture : public ::testing::Test
config_->blackboard->set<std::chrono::milliseconds>(
"bt_loop_duration",
std::chrono::milliseconds(10));
config_->blackboard->set<std::chrono::milliseconds>(
"wait_for_service_timeout",
std::chrono::milliseconds(1000));
client_ = rclcpp_action::create_client<nav2_msgs::action::Wait>(
node_, "wait");

Expand Down
18 changes: 17 additions & 1 deletion nav2_bringup/params/nav2_multirobot_params_1.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,13 @@ bt_navigator:
odom_topic: /odom
bt_loop_duration: 10
default_server_timeout: 20
wait_for_service_timeout: 1000
action_server_result_timeout: 900.0
navigators: ["navigate_to_pose", "navigate_through_poses"]
navigate_to_pose:
plugin: "nav2_bt_navigator/NavigateToPoseNavigator"
navigate_through_poses:
plugin: "nav2_bt_navigator/NavigateThroughPosesNavigator"
# 'default_nav_through_poses_bt_xml' and 'default_nav_to_pose_bt_xml' are use defaults:
# nav2_bt_navigator/navigate_to_pose_w_replanning_and_recovery.xml
# nav2_bt_navigator/navigate_through_poses_w_replanning_and_recovery.xml
Expand Down Expand Up @@ -160,7 +167,16 @@ controller_server:
trans_stopped_velocity: 0.25
short_circuit_trajectory_evaluation: True
stateful: True
critics: ["RotateToGoal", "Oscillation", "BaseObstacle", "GoalAlign", "PathAlign", "PathDist", "GoalDist"]
critics:
[
"RotateToGoal",
"Oscillation",
"BaseObstacle",
"GoalAlign",
"PathAlign",
"PathDist",
"GoalDist",
]
BaseObstacle.scale: 0.02
PathAlign.scale: 0.0
GoalAlign.scale: 0.0
Expand Down
Loading

0 comments on commit 52f0ea5

Please sign in to comment.