File tree Expand file tree Collapse file tree 4 files changed +10
-6
lines changed
behaviortree_ros2/include/behaviortree_ros2 Expand file tree Collapse file tree 4 files changed +10
-6
lines changed Original file line number Diff line number Diff line change @@ -171,6 +171,7 @@ class RosActionNode : public BT::ActionNodeBase
171
171
std::string prev_action_name_;
172
172
bool action_name_may_change_ = false ;
173
173
const std::chrono::milliseconds server_timeout_;
174
+ const std::chrono::milliseconds wait_for_server_timeout_;
174
175
175
176
private:
176
177
@@ -199,7 +200,8 @@ template<class T> inline
199
200
const RosNodeParams ¶ms):
200
201
BT::ActionNodeBase (instance_name, conf),
201
202
node_(params.nh),
202
- server_timeout_(params.server_timeout)
203
+ server_timeout_(params.server_timeout),
204
+ wait_for_server_timeout_(params.wait_for_server_timeout)
203
205
{
204
206
// Three cases:
205
207
// - we use the default action_name in RosNodeParams when port is empty
@@ -260,7 +262,7 @@ template<class T> inline
260
262
261
263
prev_action_name_ = action_name;
262
264
263
- bool found = action_client_->wait_for_action_server (server_timeout_ );
265
+ bool found = action_client_->wait_for_action_server (wait_for_server_timeout_ );
264
266
if (!found)
265
267
{
266
268
RCLCPP_ERROR (node_->get_logger (), " %s: Action server with name '%s' is not reachable." ,
Original file line number Diff line number Diff line change @@ -143,6 +143,7 @@ class RosServiceNode : public BT::ActionNodeBase
143
143
std::string prev_service_name_;
144
144
bool service_name_may_change_ = false ;
145
145
const std::chrono::milliseconds service_timeout_;
146
+ const std::chrono::milliseconds wait_for_service_timeout_;
146
147
147
148
private:
148
149
@@ -170,7 +171,8 @@ template<class T> inline
170
171
const RosNodeParams& params):
171
172
BT::ActionNodeBase (instance_name, conf),
172
173
node_(params.nh),
173
- service_timeout_(params.server_timeout)
174
+ service_timeout_(params.server_timeout),
175
+ wait_for_service_timeout_(params.wait_for_server_timeout)
174
176
{
175
177
// check port remapping
176
178
auto portIt = config ().input_ports .find (" service_name" );
@@ -225,7 +227,7 @@ template<class T> inline
225
227
service_client_ = node_->create_client <T>(service_name, rmw_qos_profile_services_default, callback_group_);
226
228
prev_service_name_ = service_name;
227
229
228
- bool found = service_client_->wait_for_service (service_timeout_ );
230
+ bool found = service_client_->wait_for_service (wait_for_service_timeout_ );
229
231
if (!found)
230
232
{
231
233
RCLCPP_ERROR (node_->get_logger (), " %s: Service with name '%s' is not reachable." ,
Original file line number Diff line number Diff line change 25
25
//
26
26
// - BT::RosActionNode
27
27
// - BT::RosServiceNode
28
- // - BT::RosServiceNode
29
28
// - BT::RosTopicPubNode
30
29
// - BT::RosTopicSubNode
31
30
//
Original file line number Diff line number Diff line change @@ -34,8 +34,9 @@ struct RosNodeParams
34
34
// - RosTopicSubNode: name of the topic to subscribe to
35
35
std::string default_port_value;
36
36
37
- // parameter used only by service client and action clients
37
+ // parameters used only by service client and action clients
38
38
std::chrono::milliseconds server_timeout = std::chrono::milliseconds(1000 );
39
+ std::chrono::milliseconds wait_for_server_timeout = std::chrono::milliseconds(500 );
39
40
};
40
41
41
42
}
You can’t perform that action at this time.
0 commit comments