Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

WIP: Make BT nodes have configurable wait times. #3960

Merged
Show file tree
Hide file tree
Changes from 1 commit
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 @@ -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_);
bt_wait_for_service_time_ =
config().blackboard->template get<std::chrono::milliseconds>("bt_wait_for_service_time");
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved

// 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(bt_wait_for_service_time_)) {
RCLCPP_ERROR(
node_->get_logger(), "\"%s\" action server not available after waiting for 1 s",
Copy link
Contributor

@tonynajjar tonynajjar Feb 28, 2024

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

you missed changing this from 1 s to "wait_for_service_timeout_" seconds

action_name.c_str());
Expand Down Expand Up @@ -462,6 +464,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 bt_wait_for_service_time_;

// 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 @@ -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_);
bt_wait_for_service_time_ =
config().blackboard->template get<std::chrono::milliseconds>("bt_wait_for_service_time");
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved

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(bt_wait_for_service_time_)) {
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 bt_wait_for_service_time_;
};

} // 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_);
bt_wait_for_service_time_ =
config().blackboard->template get<std::chrono::milliseconds>("bt_wait_for_service_time");

// 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(bt_wait_for_service_time_)) {
RCLCPP_ERROR(
node_->get_logger(), "\"%s\" service server not available after waiting for 1 s",
service_node_name.c_str());
Expand Down Expand Up @@ -248,6 +250,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 bt_wait_for_service_time_;

// To track the server response when a new request is sent
std::shared_future<typename ServiceT::Response::SharedPtr> future_result_;
Expand Down