Skip to content

Commit

Permalink
fix ci
Browse files Browse the repository at this point in the history
  • Loading branch information
MarqRazz committed May 5, 2024
1 parent a2dc8c2 commit 293bef6
Show file tree
Hide file tree
Showing 2 changed files with 46 additions and 26 deletions.
36 changes: 23 additions & 13 deletions behaviortree_ros2/include/behaviortree_ros2/bt_action_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -108,11 +108,13 @@ class RosActionNode : public BT::ActionNodeBase
*/
static PortsList providedBasicPorts(PortsList addition)
{
PortsList basic = {
InputPort<std::string>("action_name", "__default__placeholder__", "Action server name"),
InputPort<int>("server_timeout", "Action server goal timeout (mSec)"),
InputPort<int>("wait_for_server_timeout", "Action server discovery timeout (mSec)")
};
PortsList basic = { InputPort<std::string>("action_name", "__default__placeholder__",
"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 @@ -265,12 +267,16 @@ inline RosActionNode<T>::RosActionNode(const std::string& instance_name,
{
int timeout = 0;
getInput("server_timeout", timeout);
if(timeout > 0) {
if(timeout > 0)
{
server_timeout_ = std::chrono::milliseconds(timeout);
}
else {
RCLCPP_WARN(node_->get_logger(), "%s: Port `server_timeout` is not greater than zero. "
"Defaulting to %d mSec.", name().c_str(), static_cast<int>(server_timeout_.count()));
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
Expand All @@ -279,12 +285,16 @@ inline RosActionNode<T>::RosActionNode(const std::string& instance_name,
{
int timeout = 0;
getInput("wait_for_server_timeout", timeout);
if(timeout > 0) {
if(timeout > 0)
{
wait_for_server_timeout_ = std::chrono::milliseconds(timeout);
}
else {
RCLCPP_WARN(node_->get_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()));
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()));
}
}

Expand Down
36 changes: 23 additions & 13 deletions behaviortree_ros2/include/behaviortree_ros2/bt_service_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -96,11 +96,13 @@ class RosServiceNode : public BT::ActionNodeBase
*/
static PortsList providedBasicPorts(PortsList addition)
{
PortsList basic = {
InputPort<std::string>("service_name", "__default__placeholder__", "Service name"),
InputPort<int>("server_timeout", "Service server goal timeout (mSec)"),
InputPort<int>("wait_for_server_timeout", "Service server discovery timeout (mSec)")
};
PortsList basic = { InputPort<std::string>("service_name", "__default__placeholder__",
"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 @@ -236,12 +238,16 @@ inline RosServiceNode<T>::RosServiceNode(const std::string& instance_name,
{
int timeout = 0;
getInput("server_timeout", timeout);
if(timeout > 0) {
if(timeout > 0)
{
service_timeout_ = std::chrono::milliseconds(timeout);
}
else {
RCLCPP_WARN(node_->get_logger(), "%s: Port `server_timeout` is not greater than zero. "
"Defaulting to %d mSec.", name().c_str(), static_cast<int>(service_timeout_.count()));
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
Expand All @@ -250,12 +256,16 @@ inline RosServiceNode<T>::RosServiceNode(const std::string& instance_name,
{
int timeout = 0;
getInput("wait_for_server_timeout", timeout);
if(timeout > 0) {
if(timeout > 0)
{
wait_for_service_timeout_ = std::chrono::milliseconds(timeout);
}
else {
RCLCPP_WARN(node_->get_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()));
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()));
}
}

Expand Down

0 comments on commit 293bef6

Please sign in to comment.