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

Action/Server timeout option through ports #55

Open
wants to merge 3 commits into
base: humble
Choose a base branch
from
Open
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
50 changes: 46 additions & 4 deletions behaviortree_ros2/include/behaviortree_ros2/bt_action_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -109,7 +109,12 @@ class RosActionNode : public BT::ActionNodeBase
static PortsList providedBasicPorts(PortsList addition)
{
PortsList basic = { InputPort<std::string>("action_name", "__default__placeholder__",
"Action server name") };
"Action server name"),
InputPort<int>("server_timeout", "Action server goal timeout "
"(mSec)"),
InputPort<int>("wait_for_server_timeout", "Action server "
"discovery timeout "
"(mSec)") };
basic.insert(addition.begin(), addition.end());
return basic;
}
Expand Down Expand Up @@ -217,8 +222,8 @@ class RosActionNode : public BT::ActionNodeBase
std::shared_ptr<ActionClientInstance> client_instance_;
std::string action_name_;
bool action_name_may_change_ = false;
const std::chrono::milliseconds server_timeout_;
const std::chrono::milliseconds wait_for_server_timeout_;
std::chrono::milliseconds server_timeout_;
std::chrono::milliseconds wait_for_server_timeout_;
std::string action_client_key_;

private:
Expand Down Expand Up @@ -256,13 +261,50 @@ inline RosActionNode<T>::RosActionNode(const std::string& instance_name,
, server_timeout_(params.server_timeout)
, wait_for_server_timeout_(params.wait_for_server_timeout)
{
// update server_timeout_ if set throuh port and greater than 0
auto portIt = config().input_ports.find("server_timeout");
if(portIt != config().input_ports.end())
{
int timeout = 0;
getInput("server_timeout", timeout);
if(timeout > 0)
{
server_timeout_ = std::chrono::milliseconds(timeout);
}
else
{
RCLCPP_WARN(logger(),
"%s: Port `server_timeout` is not greater than zero. "
"Defaulting to %d mSec.",
name().c_str(), static_cast<int>(server_timeout_.count()));
}
}
// update wait_for_server_timeout_ if set throuh port and greater than 0
portIt = config().input_ports.find("wait_for_server_timeout");
if(portIt != config().input_ports.end())
{
int timeout = 0;
getInput("wait_for_server_timeout", timeout);
if(timeout > 0)
{
wait_for_server_timeout_ = std::chrono::milliseconds(timeout);
}
else
{
RCLCPP_WARN(logger(),
"%s: Port `wait_for_server_timeout` is not greater than zero. "
"Defaulting to %d mSec.",
name().c_str(), static_cast<int>(wait_for_server_timeout_.count()));
}
}

// Three cases:
// - we use the default action_name in RosNodeParams when port is empty
// - we use the action_name in the port and it is a static string.
// - we use the action_name in the port and it is blackboard entry.

// check port remapping
auto portIt = config().input_ports.find("action_name");
portIt = config().input_ports.find("action_name");
if(portIt != config().input_ports.end())
{
const std::string& bb_action_name = portIt->second;
Expand Down
50 changes: 46 additions & 4 deletions behaviortree_ros2/include/behaviortree_ros2/bt_service_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -97,7 +97,12 @@ class RosServiceNode : public BT::ActionNodeBase
static PortsList providedBasicPorts(PortsList addition)
{
PortsList basic = { InputPort<std::string>("service_name", "__default__placeholder__",
"Service name") };
"Service name"),
InputPort<int>("server_timeout", "Service server goal timeout "
"(mSec)"),
InputPort<int>("wait_for_server_timeout", "Service server "
"discovery timeout "
"(mSec)") };
basic.insert(addition.begin(), addition.end());
return basic;
}
Expand Down Expand Up @@ -187,8 +192,8 @@ class RosServiceNode : public BT::ActionNodeBase
std::weak_ptr<rclcpp::Node> node_;
std::string service_name_;
bool service_name_may_change_ = false;
const std::chrono::milliseconds service_timeout_;
const std::chrono::milliseconds wait_for_service_timeout_;
std::chrono::milliseconds service_timeout_;
std::chrono::milliseconds wait_for_service_timeout_;

private:
std::shared_ptr<ServiceClientInstance> srv_instance_;
Expand Down Expand Up @@ -227,8 +232,45 @@ inline RosServiceNode<T>::RosServiceNode(const std::string& instance_name,
, service_timeout_(params.server_timeout)
, wait_for_service_timeout_(params.wait_for_server_timeout)
{
// update service_timeout_ if set throuh port and greater than 0
auto portIt = config().input_ports.find("server_timeout");
if(portIt != config().input_ports.end())
{
int timeout = 0;
getInput("server_timeout", timeout);
if(timeout > 0)
{
service_timeout_ = std::chrono::milliseconds(timeout);
}
else
{
RCLCPP_WARN(logger(),
"%s: Port `server_timeout` is not greater than zero. "
"Defaulting to %d mSec.",
name().c_str(), static_cast<int>(service_timeout_.count()));
}
}
// update wait_for_service_timeout_ if set throuh port and greater than 0
portIt = config().input_ports.find("wait_for_server_timeout");
if(portIt != config().input_ports.end())
{
int timeout = 0;
getInput("wait_for_server_timeout", timeout);
if(timeout > 0)
{
wait_for_service_timeout_ = std::chrono::milliseconds(timeout);
}
else
{
RCLCPP_WARN(logger(),
"%s: Port `wait_for_server_timeout` is not greater than zero. "
"Defaulting to %d mSec.",
name().c_str(), static_cast<int>(wait_for_service_timeout_.count()));
}
}

// check port remapping
auto portIt = config().input_ports.find("service_name");
portIt = config().input_ports.find("service_name");
if(portIt != config().input_ports.end())
{
const std::string& bb_service_name = portIt->second;
Expand Down
Loading