Skip to content

Commit 293bef6

Browse files
committed
fix ci
1 parent a2dc8c2 commit 293bef6

File tree

2 files changed

+46
-26
lines changed

2 files changed

+46
-26
lines changed

behaviortree_ros2/include/behaviortree_ros2/bt_action_node.hpp

+23-13
Original file line numberDiff line numberDiff line change
@@ -108,11 +108,13 @@ class RosActionNode : public BT::ActionNodeBase
108108
*/
109109
static PortsList providedBasicPorts(PortsList addition)
110110
{
111-
PortsList basic = {
112-
InputPort<std::string>("action_name", "__default__placeholder__", "Action server name"),
113-
InputPort<int>("server_timeout", "Action server goal timeout (mSec)"),
114-
InputPort<int>("wait_for_server_timeout", "Action server discovery timeout (mSec)")
115-
};
111+
PortsList basic = { InputPort<std::string>("action_name", "__default__placeholder__",
112+
"Action server name"),
113+
InputPort<int>("server_timeout", "Action server goal timeout "
114+
"(mSec)"),
115+
InputPort<int>("wait_for_server_timeout", "Action server "
116+
"discovery timeout "
117+
"(mSec)") };
116118
basic.insert(addition.begin(), addition.end());
117119
return basic;
118120
}
@@ -265,12 +267,16 @@ inline RosActionNode<T>::RosActionNode(const std::string& instance_name,
265267
{
266268
int timeout = 0;
267269
getInput("server_timeout", timeout);
268-
if(timeout > 0) {
270+
if(timeout > 0)
271+
{
269272
server_timeout_ = std::chrono::milliseconds(timeout);
270273
}
271-
else {
272-
RCLCPP_WARN(node_->get_logger(), "%s: Port `server_timeout` is not greater than zero. "
273-
"Defaulting to %d mSec.", name().c_str(), static_cast<int>(server_timeout_.count()));
274+
else
275+
{
276+
RCLCPP_WARN(logger(),
277+
"%s: Port `server_timeout` is not greater than zero. "
278+
"Defaulting to %d mSec.",
279+
name().c_str(), static_cast<int>(server_timeout_.count()));
274280
}
275281
}
276282
// update wait_for_server_timeout_ if set throuh port and greater than 0
@@ -279,12 +285,16 @@ inline RosActionNode<T>::RosActionNode(const std::string& instance_name,
279285
{
280286
int timeout = 0;
281287
getInput("wait_for_server_timeout", timeout);
282-
if(timeout > 0) {
288+
if(timeout > 0)
289+
{
283290
wait_for_server_timeout_ = std::chrono::milliseconds(timeout);
284291
}
285-
else {
286-
RCLCPP_WARN(node_->get_logger(), "%s: Port `wait_for_server_timeout` is not greater than zero. "
287-
"Defaulting to %d mSec.", name().c_str(), static_cast<int>(wait_for_server_timeout_.count()));
292+
else
293+
{
294+
RCLCPP_WARN(logger(),
295+
"%s: Port `wait_for_server_timeout` is not greater than zero. "
296+
"Defaulting to %d mSec.",
297+
name().c_str(), static_cast<int>(wait_for_server_timeout_.count()));
288298
}
289299
}
290300

behaviortree_ros2/include/behaviortree_ros2/bt_service_node.hpp

+23-13
Original file line numberDiff line numberDiff line change
@@ -96,11 +96,13 @@ class RosServiceNode : public BT::ActionNodeBase
9696
*/
9797
static PortsList providedBasicPorts(PortsList addition)
9898
{
99-
PortsList basic = {
100-
InputPort<std::string>("service_name", "__default__placeholder__", "Service name"),
101-
InputPort<int>("server_timeout", "Service server goal timeout (mSec)"),
102-
InputPort<int>("wait_for_server_timeout", "Service server discovery timeout (mSec)")
103-
};
99+
PortsList basic = { InputPort<std::string>("service_name", "__default__placeholder__",
100+
"Service name"),
101+
InputPort<int>("server_timeout", "Service server goal timeout "
102+
"(mSec)"),
103+
InputPort<int>("wait_for_server_timeout", "Service server "
104+
"discovery timeout "
105+
"(mSec)") };
104106
basic.insert(addition.begin(), addition.end());
105107
return basic;
106108
}
@@ -236,12 +238,16 @@ inline RosServiceNode<T>::RosServiceNode(const std::string& instance_name,
236238
{
237239
int timeout = 0;
238240
getInput("server_timeout", timeout);
239-
if(timeout > 0) {
241+
if(timeout > 0)
242+
{
240243
service_timeout_ = std::chrono::milliseconds(timeout);
241244
}
242-
else {
243-
RCLCPP_WARN(node_->get_logger(), "%s: Port `server_timeout` is not greater than zero. "
244-
"Defaulting to %d mSec.", name().c_str(), static_cast<int>(service_timeout_.count()));
245+
else
246+
{
247+
RCLCPP_WARN(logger(),
248+
"%s: Port `server_timeout` is not greater than zero. "
249+
"Defaulting to %d mSec.",
250+
name().c_str(), static_cast<int>(service_timeout_.count()));
245251
}
246252
}
247253
// update wait_for_service_timeout_ if set throuh port and greater than 0
@@ -250,12 +256,16 @@ inline RosServiceNode<T>::RosServiceNode(const std::string& instance_name,
250256
{
251257
int timeout = 0;
252258
getInput("wait_for_server_timeout", timeout);
253-
if(timeout > 0) {
259+
if(timeout > 0)
260+
{
254261
wait_for_service_timeout_ = std::chrono::milliseconds(timeout);
255262
}
256-
else {
257-
RCLCPP_WARN(node_->get_logger(), "%s: Port `wait_for_server_timeout` is not greater than zero. "
258-
"Defaulting to %d mSec.", name().c_str(), static_cast<int>(wait_for_service_timeout_.count()));
263+
else
264+
{
265+
RCLCPP_WARN(logger(),
266+
"%s: Port `wait_for_server_timeout` is not greater than zero. "
267+
"Defaulting to %d mSec.",
268+
name().c_str(), static_cast<int>(wait_for_service_timeout_.count()));
259269
}
260270
}
261271

0 commit comments

Comments
 (0)