|
17 | 17 | from rclpy.event_handler import QoSPublisherMatchedInfo
|
18 | 18 | from rclpy.event_handler import QoSSubscriptionMatchedInfo
|
19 | 19 | from rclpy.event_handler import SubscriptionEventCallbacks
|
| 20 | +from rclpy.executors import ExternalShutdownException |
20 | 21 | from rclpy.executors import SingleThreadedExecutor
|
21 | 22 | from rclpy.node import Node
|
22 | 23 | from rclpy.publisher import Publisher
|
@@ -133,72 +134,69 @@ def destroy_one_pub(self, pub: Publisher):
|
133 | 134 |
|
134 | 135 |
|
135 | 136 | def main(args=None):
|
136 |
| - rclpy.init(args=args) |
137 |
| - |
138 |
| - topic_name_for_detect_pub_matched_event = 'pub_topic_matched_event_detect' |
139 |
| - topic_name_for_detect_sub_matched_event = 'sub_topic_matched_event_detect' |
140 |
| - |
141 |
| - matched_event_detect_node = MatchedEventDetectNode( |
142 |
| - topic_name_for_detect_pub_matched_event, topic_name_for_detect_sub_matched_event) |
143 |
| - multi_subs_node = MultiSubNode(topic_name_for_detect_pub_matched_event) |
144 |
| - multi_pubs_node = MultiPubNode(topic_name_for_detect_sub_matched_event) |
145 |
| - |
146 |
| - maximum_wait_time = 10 # 10s |
147 |
| - |
148 |
| - executor = SingleThreadedExecutor() |
149 |
| - |
150 |
| - executor.add_node(matched_event_detect_node) |
151 |
| - executor.add_node(multi_subs_node) |
152 |
| - executor.add_node(multi_pubs_node) |
153 |
| - |
154 |
| - # MatchedEventDetectNode will output: |
155 |
| - # First subscription is connected. |
156 |
| - sub1 = multi_subs_node.create_one_sub() |
157 |
| - executor.spin_until_future_complete(matched_event_detect_node.get_future(), maximum_wait_time) |
158 |
| - |
159 |
| - # MatchedEventDetectNode will output: |
160 |
| - # The changed number of connected subscription is 1 and current number of connected |
161 |
| - # subscription is 2. |
162 |
| - sub2 = multi_subs_node.create_one_sub() |
163 |
| - executor.spin_until_future_complete(matched_event_detect_node.get_future(), maximum_wait_time) |
164 |
| - |
165 |
| - # MatchedEventDetectNode will output: |
166 |
| - # The changed number of connected subscription is -1 and current number of connected |
167 |
| - # subscription is 1. |
168 |
| - multi_subs_node.destroy_one_sub(sub1) |
169 |
| - executor.spin_until_future_complete(matched_event_detect_node.get_future(), maximum_wait_time) |
170 |
| - |
171 |
| - # MatchedEventDetectNode will output: |
172 |
| - # Last subscription is disconnected. |
173 |
| - multi_subs_node.destroy_one_sub(sub2) |
174 |
| - executor.spin_until_future_complete(matched_event_detect_node.get_future(), maximum_wait_time) |
175 |
| - |
176 |
| - # MatchedEventDetectNode will output: |
177 |
| - # First publisher is connected. |
178 |
| - pub1 = multi_pubs_node.create_one_pub() |
179 |
| - executor.spin_until_future_complete(matched_event_detect_node.get_future(), maximum_wait_time) |
180 |
| - |
181 |
| - # MatchedEventDetectNode will output: |
182 |
| - # The changed number of connected publisher is 1 and current number of connected publisher |
183 |
| - # is 2. |
184 |
| - pub2 = multi_pubs_node.create_one_pub() |
185 |
| - executor.spin_until_future_complete(matched_event_detect_node.get_future(), maximum_wait_time) |
186 |
| - |
187 |
| - # MatchedEventDetectNode will output: |
188 |
| - # The changed number of connected publisher is -1 and current number of connected publisher |
189 |
| - # is 1. |
190 |
| - multi_pubs_node.destroy_one_pub(pub1) |
191 |
| - executor.spin_until_future_complete(matched_event_detect_node.get_future(), maximum_wait_time) |
192 |
| - |
193 |
| - # MatchedEventDetectNode will output: |
194 |
| - # Last publisher is disconnected. |
195 |
| - multi_pubs_node.destroy_one_pub(pub2) |
196 |
| - executor.spin_until_future_complete(matched_event_detect_node.get_future(), maximum_wait_time) |
197 |
| - |
198 |
| - multi_pubs_node.destroy_node() |
199 |
| - multi_subs_node.destroy_node() |
200 |
| - matched_event_detect_node.destroy_node() |
201 |
| - rclpy.try_shutdown() |
| 137 | + try: |
| 138 | + with rclpy.init(args=args): |
| 139 | + topic_name_for_detect_pub_matched_event = 'pub_topic_matched_event_detect' |
| 140 | + topic_name_for_detect_sub_matched_event = 'sub_topic_matched_event_detect' |
| 141 | + |
| 142 | + matched_node = MatchedEventDetectNode( |
| 143 | + topic_name_for_detect_pub_matched_event, topic_name_for_detect_sub_matched_event) |
| 144 | + multi_subs_node = MultiSubNode(topic_name_for_detect_pub_matched_event) |
| 145 | + multi_pubs_node = MultiPubNode(topic_name_for_detect_sub_matched_event) |
| 146 | + |
| 147 | + max_wait_time = 10 # 10s |
| 148 | + |
| 149 | + executor = SingleThreadedExecutor() |
| 150 | + |
| 151 | + executor.add_node(matched_node) |
| 152 | + executor.add_node(multi_subs_node) |
| 153 | + executor.add_node(multi_pubs_node) |
| 154 | + |
| 155 | + # MatchedEventDetectNode will output: |
| 156 | + # First subscription is connected. |
| 157 | + sub1 = multi_subs_node.create_one_sub() |
| 158 | + executor.spin_until_future_complete(matched_node.get_future(), max_wait_time) |
| 159 | + |
| 160 | + # MatchedEventDetectNode will output: |
| 161 | + # The changed number of connected subscription is 1 and current number of connected |
| 162 | + # subscription is 2. |
| 163 | + sub2 = multi_subs_node.create_one_sub() |
| 164 | + executor.spin_until_future_complete(matched_node.get_future(), max_wait_time) |
| 165 | + |
| 166 | + # MatchedEventDetectNode will output: |
| 167 | + # The changed number of connected subscription is -1 and current number of connected |
| 168 | + # subscription is 1. |
| 169 | + multi_subs_node.destroy_one_sub(sub1) |
| 170 | + executor.spin_until_future_complete(matched_node.get_future(), max_wait_time) |
| 171 | + |
| 172 | + # MatchedEventDetectNode will output: |
| 173 | + # Last subscription is disconnected. |
| 174 | + multi_subs_node.destroy_one_sub(sub2) |
| 175 | + executor.spin_until_future_complete(matched_node.get_future(), max_wait_time) |
| 176 | + |
| 177 | + # MatchedEventDetectNode will output: |
| 178 | + # First publisher is connected. |
| 179 | + pub1 = multi_pubs_node.create_one_pub() |
| 180 | + executor.spin_until_future_complete(matched_node.get_future(), max_wait_time) |
| 181 | + |
| 182 | + # MatchedEventDetectNode will output: |
| 183 | + # The changed number of connected publisher is 1 and current number of connected |
| 184 | + # publisher is 2. |
| 185 | + pub2 = multi_pubs_node.create_one_pub() |
| 186 | + executor.spin_until_future_complete(matched_node.get_future(), max_wait_time) |
| 187 | + |
| 188 | + # MatchedEventDetectNode will output: |
| 189 | + # The changed number of connected publisher is -1 and current number of connected |
| 190 | + # publisher is 1. |
| 191 | + multi_pubs_node.destroy_one_pub(pub1) |
| 192 | + executor.spin_until_future_complete(matched_node.get_future(), max_wait_time) |
| 193 | + |
| 194 | + # MatchedEventDetectNode will output: |
| 195 | + # Last publisher is disconnected. |
| 196 | + multi_pubs_node.destroy_one_pub(pub2) |
| 197 | + executor.spin_until_future_complete(matched_node.get_future(), max_wait_time) |
| 198 | + except (KeyboardInterrupt, ExternalShutdownException): |
| 199 | + pass |
202 | 200 |
|
203 | 201 |
|
204 | 202 | if __name__ == '__main__':
|
|
0 commit comments