Skip to content

Commit b248cd0

Browse files
committed
Add send_action_goals_in_new_thread param
1 parent 5d93ca0 commit b248cd0

File tree

6 files changed

+15
-5
lines changed

6 files changed

+15
-5
lines changed

rosbridge_library/src/rosbridge_library/capabilities/send_action_goal.py

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -56,21 +56,21 @@ def __init__(self, protocol):
5656
Capability.__init__(self, protocol)
5757

5858
# Register the operations that this capability provides
59-
call_services_in_new_thread = (
60-
protocol.node_handle.get_parameter("call_services_in_new_thread")
59+
send_action_goals_in_new_thread = (
60+
protocol.node_handle.get_parameter("send_action_goals_in_new_thread")
6161
.get_parameter_value()
6262
.bool_value
6363
)
64-
if call_services_in_new_thread:
64+
if send_action_goals_in_new_thread:
6565
# Sends the action goal in a separate thread so multiple actions can be processed simultaneously.
66-
protocol.node_handle.get_logger().info("Sending action goal in new thread")
66+
protocol.node_handle.get_logger().info("Sending action goals in new thread")
6767
protocol.register_operation(
6868
"send_action_goal",
6969
lambda msg: Thread(target=self.send_action_goal, args=(msg,)).start(),
7070
)
7171
else:
7272
# Sends the actions goal in this thread, so actions block and must be processed sequentially.
73-
protocol.node_handle.get_logger().info("Sending action goal in existing thread")
73+
protocol.node_handle.get_logger().info("Sending action goals in existing thread")
7474
protocol.register_operation("send_action_goal", self.send_action_goal)
7575

7676
protocol.register_operation("cancel_action_goal", self.cancel_action_goal)

rosbridge_library/test/capabilities/test_action_capabilities.py

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -29,6 +29,7 @@ def setUp(self):
2929
self.executor.add_node(self.node)
3030

3131
self.node.declare_parameter("call_services_in_new_thread", False)
32+
self.node.declare_parameter("send_action_goals_in_new_thread", False)
3233

3334
self.proto = Protocol(self._testMethodName, self.node)
3435
# change the log function so we can verify errors are logged

rosbridge_library/test/capabilities/test_call_service.py

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -40,6 +40,7 @@ def setUp(self):
4040
self.executor.add_node(self.node)
4141

4242
self.node.declare_parameter("call_services_in_new_thread", False)
43+
self.node.declare_parameter("send_action_goals_in_new_thread", False)
4344

4445
# Create service servers with a separate callback group
4546
self.cb_group = ReentrantCallbackGroup()

rosbridge_library/test/capabilities/test_service_capabilities.py

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -23,6 +23,7 @@ def setUp(self):
2323
self.node = Node("test_service_capabilities")
2424

2525
self.node.declare_parameter("call_services_in_new_thread", False)
26+
self.node.declare_parameter("send_action_goals_in_new_thread", False)
2627

2728
self.proto = Protocol(self._testMethodName, self.node)
2829
# change the log function so we can verify errors are logged

rosbridge_server/launch/rosbridge_websocket_launch.xml

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,7 @@
1414

1515
<arg name="use_compression" default="false" />
1616
<arg name="call_services_in_new_thread" default="false" />
17+
<arg name="send_action_goals_in_new_thread" default="false" />
1718

1819
<arg name="topics_glob" default="" />
1920
<arg name="services_glob" default="" />
@@ -35,6 +36,7 @@
3536
<param name="unregister_timeout" value="$(var unregister_timeout)"/>
3637
<param name="use_compression" value="$(var use_compression)"/>
3738
<param name="call_services_in_new_thread" value="$(var call_services_in_new_thread)"/>
39+
<param name="send_action_goals_in_new_thread" value="$(var send_action_goals_in_new_thread)"/>
3840

3941
<param name="topics_glob" value="$(var topics_glob)"/>
4042
<param name="services_glob" value="$(var services_glob)"/>
@@ -52,6 +54,7 @@
5254
<param name="unregister_timeout" value="$(var unregister_timeout)"/>
5355
<param name="use_compression" value="$(var use_compression)"/>
5456
<param name="call_services_in_new_thread" value="$(var call_services_in_new_thread)"/>
57+
<param name="send_action_goals_in_new_thread" value="$(var send_action_goals_in_new_thread)"/>
5558

5659
<param name="topics_glob" value="$(var topics_glob)"/>
5760
<param name="services_glob" value="$(var services_glob)"/>

rosbridge_server/scripts/rosbridge_websocket.py

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -178,6 +178,10 @@ def protocol_parameter_handling(self):
178178
"call_services_in_new_thread", False
179179
).value
180180

181+
RosbridgeWebSocket.send_action_goals_in_new_thread = self.declare_parameter(
182+
"send_action_goals_in_new_thread", False
183+
).value
184+
181185
# get RosbridgeProtocol parameters
182186
RosbridgeWebSocket.fragment_timeout = self.declare_parameter(
183187
"fragment_timeout", RosbridgeWebSocket.fragment_timeout

0 commit comments

Comments
 (0)