|
| 1 | +# Copyright 2019 Open Source Robotics Foundation, Inc. |
| 2 | +# |
| 3 | +# Licensed under the Apache License, Version 2.0 (the "License"); |
| 4 | +# you may not use this file except in compliance with the License. |
| 5 | +# You may obtain a copy of the License at |
| 6 | +# |
| 7 | +# http://www.apache.org/licenses/LICENSE-2.0 |
| 8 | +# |
| 9 | +# Unless required by applicable law or agreed to in writing, software |
| 10 | +# distributed under the License is distributed on an "AS IS" BASIS, |
| 11 | +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 12 | +# See the License for the specific language governing permissions and |
| 13 | +# limitations under the License. |
| 14 | + |
| 15 | +import asyncio |
| 16 | + |
| 17 | +import rclpy |
| 18 | +from example_interfaces.action import Fibonacci |
| 19 | +from rclpy.action import ActionServer, CancelResponse, GoalResponse |
| 20 | +from rclpy.callback_groups import ReentrantCallbackGroup |
| 21 | +from rclpy.executors import MultiThreadedExecutor |
| 22 | +from rclpy.node import Node |
| 23 | + |
| 24 | + |
| 25 | +def asyncio_loop(func): |
| 26 | + def wrapper(*args, **kwargs): |
| 27 | + return asyncio.new_event_loop().run_until_complete( |
| 28 | + func(*args, **kwargs)) |
| 29 | + |
| 30 | + return wrapper |
| 31 | + |
| 32 | + |
| 33 | +class MinimalActionServerAsyncIO(Node): |
| 34 | + |
| 35 | + def __init__(self): |
| 36 | + super().__init__('minimal_action_server_asyncio') |
| 37 | + |
| 38 | + self._action_server = ActionServer( |
| 39 | + self, |
| 40 | + Fibonacci, |
| 41 | + 'fibonacci', |
| 42 | + execute_callback=self.execute_callback, |
| 43 | + callback_group=ReentrantCallbackGroup(), |
| 44 | + goal_callback=self.goal_callback, |
| 45 | + cancel_callback=self.cancel_callback) |
| 46 | + |
| 47 | + def destroy(self): |
| 48 | + self._action_server.destroy() |
| 49 | + super().destroy_node() |
| 50 | + |
| 51 | + def goal_callback(self, goal_request): |
| 52 | + """Accept or reject a client request to begin an action.""" |
| 53 | + # This server allows multiple goals in parallel |
| 54 | + self.get_logger().info('Received goal request') |
| 55 | + return GoalResponse.ACCEPT |
| 56 | + |
| 57 | + def cancel_callback(self, goal_handle): |
| 58 | + """Accept or reject a client request to cancel an action.""" |
| 59 | + self.get_logger().info('Received cancel request') |
| 60 | + return CancelResponse.ACCEPT |
| 61 | + |
| 62 | + @asyncio_loop |
| 63 | + async def execute_callback(self, goal_handle): |
| 64 | + """Execute a goal.""" |
| 65 | + self.get_logger().info('Executing goal...') |
| 66 | + |
| 67 | + # Append the seeds for the Fibonacci sequence |
| 68 | + feedback_msg = Fibonacci.Feedback() |
| 69 | + feedback_msg.sequence = [0, 1] |
| 70 | + |
| 71 | + # Start executing the action |
| 72 | + for i in range(1, goal_handle.request.order): |
| 73 | + if goal_handle.is_cancel_requested: |
| 74 | + goal_handle.canceled() |
| 75 | + self.get_logger().info('Goal canceled') |
| 76 | + return Fibonacci.Result() |
| 77 | + |
| 78 | + # Update Fibonacci sequence |
| 79 | + feedback_msg.sequence.append( |
| 80 | + feedback_msg.sequence[i] + feedback_msg.sequence[i - 1]) |
| 81 | + |
| 82 | + self.get_logger().info( |
| 83 | + 'Publishing feedback: {0}'.format(feedback_msg.sequence)) |
| 84 | + |
| 85 | + # Publish the feedback |
| 86 | + goal_handle.publish_feedback(feedback_msg) |
| 87 | + |
| 88 | + # Sleep for demonstration purposes |
| 89 | + await asyncio.sleep(1) |
| 90 | + |
| 91 | + goal_handle.succeed() |
| 92 | + |
| 93 | + # Populate result message |
| 94 | + result = Fibonacci.Result() |
| 95 | + result.sequence = feedback_msg.sequence |
| 96 | + |
| 97 | + self.get_logger().info('Returning result: {0}'.format(result.sequence)) |
| 98 | + |
| 99 | + return result |
| 100 | + |
| 101 | + |
| 102 | +def main(args=None): |
| 103 | + # init ros2 |
| 104 | + rclpy.init(args=args) |
| 105 | + |
| 106 | + # Use a MultiThreadedExecutor to enable processing goals concurrently |
| 107 | + executor = MultiThreadedExecutor() |
| 108 | + |
| 109 | + # create node |
| 110 | + action_server = MinimalActionServerAsyncIO() |
| 111 | + |
| 112 | + # add node |
| 113 | + executor.add_node(action_server) |
| 114 | + |
| 115 | + # spin |
| 116 | + executor.spin() |
| 117 | + |
| 118 | + action_server.destroy() |
| 119 | + rclpy.shutdown() |
| 120 | + |
| 121 | + |
| 122 | +if __name__ == '__main__': |
| 123 | + main() |
0 commit comments