-
Notifications
You must be signed in to change notification settings - Fork 1
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
SingleThreadedExecutor with awaited service call doesn't process othe…
…r callbacks when rclpy.spin is passed a timeout ros2/rclpy#1159 Signed-off-by: Tomoya Fujita <[email protected]>
- Loading branch information
1 parent
544e615
commit 196683d
Showing
2 changed files
with
52 additions
and
0 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,51 @@ | ||
import rclpy | ||
from rclpy.node import Node | ||
from rclpy.callback_groups import ReentrantCallbackGroup | ||
from rclpy.task import Future | ||
|
||
# Random service example. | ||
from rcl_interfaces.srv import GetParameters | ||
|
||
|
||
class AsyncClient(Node): | ||
def __init__(self): | ||
super().__init__("async_client_node") | ||
callback_group = ReentrantCallbackGroup() | ||
|
||
self.cli = self.create_client( | ||
GetParameters, "test_service", callback_group=callback_group | ||
) | ||
self.service_call_timer = self.create_timer( | ||
1.0, self.call_service_cb, callback_group=callback_group | ||
) | ||
self.log_timer = self.create_timer( | ||
2.0, | ||
self.log_cb, | ||
callback_group=callback_group, | ||
) | ||
|
||
def log_cb(self): | ||
self.get_logger().info("Logging timer fired.") | ||
|
||
async def call_service_cb(self): | ||
self.service_call_timer.cancel() | ||
|
||
self.get_logger().info("Calling service") | ||
# I know there's no service, this is intentional and I expect this task to not complete, | ||
# but other tasks should still be able to complete! | ||
response = await self.cli.call_async(GetParameters.Request()) | ||
self.get_logger().info(f"Service call response: {response.message}") | ||
|
||
|
||
def main(args=None): | ||
rclpy.init() | ||
node = AsyncClient() | ||
|
||
# If I run this, my log_cb is called. | ||
#rclpy.spin_until_future_complete(node, Future()) | ||
# If I run this, my log_cb isn't called! | ||
rclpy.spin_until_future_complete(node, Future(), timeout_sec=5.0) | ||
|
||
|
||
if __name__ == '__main__': | ||
main() |