Skip to content

Commit 96d0000

Browse files
authored
Add rclpy message lost status event demo (#457)
Signed-off-by: Ivan Santiago Paunovic <[email protected]>
1 parent ce4423c commit 96d0000

File tree

3 files changed

+80
-2
lines changed

3 files changed

+80
-2
lines changed

quality_of_service_demo/README.md

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -161,6 +161,7 @@ export RMW_IMPLEMENTATION = rmw_connext_cpp
161161
ros2 run quality_of_service_demo_cpp message_lost_listener &
162162
# -s allows specifying the message size in KiB. This argument is optional, defaults to 8192KiB.
163163
ros2 run quality_of_service_demo_cpp message_lost_talker -s 8192
164+
# ros2 run quality_of_service_demo_py message_lost_talker -s 8192 to run the python listener.
164165
```
165166

166167
Example output:
Lines changed: 76 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,76 @@
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()

quality_of_service_demo/rclpy/setup.py

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -27,10 +27,11 @@
2727
tests_require=['pytest'],
2828
entry_points={
2929
'console_scripts': [
30-
'lifespan = quality_of_service_demo_py.lifespan:main',
31-
'liveliness = quality_of_service_demo_py.liveliness:main',
3230
'deadline = quality_of_service_demo_py.deadline:main',
3331
'incompatible_qos = quality_of_service_demo_py.incompatible_qos:main',
32+
'lifespan = quality_of_service_demo_py.lifespan:main',
33+
'liveliness = quality_of_service_demo_py.liveliness:main',
34+
'message_lost_listener = quality_of_service_demo_py.message_lost_listener:main',
3435
],
3536
},
3637
)

0 commit comments

Comments
 (0)