|
| 1 | +# Copyright 2020 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 rclpy |
| 16 | +from rclpy.executors import SingleThreadedExecutor |
| 17 | +from rclpy.node import Node |
| 18 | +from rclpy.qos_event import SubscriptionEventCallbacks |
| 19 | +from rclpy.time import Time |
| 20 | + |
| 21 | +from sensor_msgs.msg import Image |
| 22 | + |
| 23 | + |
| 24 | +class MessageLostListener(Node): |
| 25 | + """Listener node to demonstrate how to get a notification on lost messages.""" |
| 26 | + |
| 27 | + def __init__(self): |
| 28 | + """Create a MessageLostListener.""" |
| 29 | + super().__init__('message_lost_listener') |
| 30 | + |
| 31 | + # Create an object describing the event handlers that will |
| 32 | + # be registered in the subscription. |
| 33 | + # In this case, only a handler for a message lost event is registered. |
| 34 | + event_callbacks = SubscriptionEventCallbacks( |
| 35 | + message_lost=self._message_lost_event_callback) |
| 36 | + # Create a subscription, passing the previously created event handlers. |
| 37 | + self.subscription = self.create_subscription( |
| 38 | + Image, |
| 39 | + 'message_lost_chatter', |
| 40 | + self._message_callback, |
| 41 | + 1, |
| 42 | + event_callbacks=event_callbacks) |
| 43 | + |
| 44 | + def _message_callback(self, message): |
| 45 | + """Log when a message is received.""" |
| 46 | + now = self.get_clock().now() |
| 47 | + diff = now - Time.from_msg(message.header.stamp) |
| 48 | + self.get_logger().info( |
| 49 | + f'I heard an Image. Message single trip latency: [{diff.nanoseconds}]\n---') |
| 50 | + |
| 51 | + def _message_lost_event_callback(self, message_lost_status): |
| 52 | + """Log the number of lost messages when the event is triggered.""" |
| 53 | + self.get_logger().info( |
| 54 | + 'Some messages were lost:\n>\tNumber of new lost messages: ' |
| 55 | + f'{message_lost_status.total_count_change}' |
| 56 | + f' \n>\tTotal number of messages lost: {message_lost_status.total_count}', |
| 57 | + ) |
| 58 | + |
| 59 | + |
| 60 | +def main(): |
| 61 | + rclpy.init(args=None) |
| 62 | + |
| 63 | + listener = MessageLostListener() |
| 64 | + executor = SingleThreadedExecutor() |
| 65 | + executor.add_node(listener) |
| 66 | + |
| 67 | + try: |
| 68 | + executor.spin() |
| 69 | + except KeyboardInterrupt: |
| 70 | + pass |
| 71 | + finally: |
| 72 | + rclpy.shutdown() |
| 73 | + |
| 74 | + |
| 75 | +if __name__ == '__main__': |
| 76 | + main() |
0 commit comments