Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

QoS overrides demo in python #479

Merged
merged 3 commits into from
Jan 8, 2021
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 2 additions & 0 deletions quality_of_service_demo/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -194,3 +194,5 @@ in another terminal:
```
ros2 run quality_of_service_demo_cpp qos_overrides_listener --ros-args --params-file /path/to/yaml/file
```

There are similar qos_overrides_talker/qos_overrides_listener executables in `quality_of_service_demo_py`.
Original file line number Diff line number Diff line change
@@ -0,0 +1,61 @@
# Copyright 2021 Open Source Robotics Foundation, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

import rclpy
from rclpy.node import Node
from rclpy.qos_overriding_options import QosCallbackResult
from rclpy.qos_overriding_options import QoSOverridingOptions

from std_msgs.msg import String


class Listener(Node):

def __init__(self):
super().__init__('qos_overrides_listener')
self.sub = self.create_subscription(
String, 'qos_overrides_chatter', self.chatter_callback, 10,
qos_overriding_options=QoSOverridingOptions.with_default_policies(
callback=self.qos_callback,
# entity_id='my_custom_id', # Use this if you want a custo qos override id.
))

def chatter_callback(self, msg):
self.get_logger().info('I heard: [%s]' % msg.data)

def qos_callback(self, qos):
result = QosCallbackResult()
if qos.depth <= 10:
result.successful = True
return result
result.successful = False
result.reason = 'expected qos depth less than 10'
return result


def main(args=None):
rclpy.init(args=args)

node = Listener()
try:
rclpy.spin(node)
except KeyboardInterrupt:
pass

node.destroy_node()
rclpy.shutdown()


if __name__ == '__main__':
main()
Original file line number Diff line number Diff line change
@@ -0,0 +1,69 @@
# Copyright 2021 Open Source Robotics Foundation, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

import rclpy
from rclpy.node import Node
from rclpy.qos_overriding_options import QosCallbackResult
from rclpy.qos_overriding_options import QoSOverridingOptions

from std_msgs.msg import String


class Talker(Node):

def __init__(self):
super().__init__('qos_overrides_talker')
self.i = 0
self.pub = self.create_publisher(
String, 'qos_overrides_chatter', 10,
qos_overriding_options=QoSOverridingOptions.with_default_policies(
callback=self.qos_callback,
# entity_id='my_custom_id', # Use this if you want a custo qos override id.
))
timer_period = 1.0
self.tmr = self.create_timer(timer_period, self.timer_callback)

def timer_callback(self):
msg = String()
msg.data = 'Hello World: {0}'.format(self.i)
self.i += 1
self.get_logger().info('Publishing: "{0}"'.format(msg.data))
self.pub.publish(msg)

def qos_callback(self, qos):
result = QosCallbackResult()
if qos.depth <= 10:
result.successful = True
return result
result.successful = False
result.reason = 'expected qos depth less than 10'
return result


def main(args=None):
rclpy.init(args=args)

node = Talker()

try:
rclpy.spin(node)
except KeyboardInterrupt:
pass

node.destroy_node()
rclpy.shutdown()


if __name__ == '__main__':
main()
2 changes: 2 additions & 0 deletions quality_of_service_demo/rclpy/setup.py
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,8 @@
'lifespan = quality_of_service_demo_py.lifespan:main',
'liveliness = quality_of_service_demo_py.liveliness:main',
'message_lost_listener = quality_of_service_demo_py.message_lost_listener:main',
'qos_overrides_listener = quality_of_service_demo_py.qos_overrides_listener:main',
'qos_overrides_talker = quality_of_service_demo_py.qos_overrides_talker:main',
],
},
)