|
| 1 | +# Copyright 2017 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 | +from time import sleep |
| 16 | +from typing import Optional |
| 17 | + |
| 18 | +import rclpy |
| 19 | + |
| 20 | +from argparse import ArgumentParser |
| 21 | +from rclpy.expand_topic_name import expand_topic_name |
| 22 | +from rclpy.topic_or_service_is_hidden import topic_or_service_is_hidden |
| 23 | +from rclpy.validate_full_topic_name import validate_full_topic_name |
| 24 | +from rosidl_runtime_py import get_message_interfaces |
| 25 | +from rosidl_runtime_py import message_to_yaml |
| 26 | +from rosidl_runtime_py.utilities import get_message |
| 27 | + |
| 28 | + |
| 29 | +def profile_configure_short_keys( |
| 30 | + profile: rclpy.qos.QoSProfile = None, reliability: str = None, |
| 31 | + durability: str = None, depth: Optional[int] = None, history: str = None, |
| 32 | +) -> rclpy.qos.QoSProfile: |
| 33 | + """Configure a QoSProfile given a profile, and optional overrides.""" |
| 34 | + if history: |
| 35 | + profile.history = rclpy.qos.QoSHistoryPolicy.get_from_short_key(history) |
| 36 | + if durability: |
| 37 | + profile.durability = rclpy.qos.QoSDurabilityPolicy.get_from_short_key(durability) |
| 38 | + if reliability: |
| 39 | + profile.reliability = rclpy.qos.QoSReliabilityPolicy.get_from_short_key(reliability) |
| 40 | + if depth and depth >= 0: |
| 41 | + profile.depth = depth |
| 42 | + else: |
| 43 | + if (profile.durability == rclpy.qos.QoSDurabilityPolicy.TRANSIENT_LOCAL |
| 44 | + and profile.depth == 0): |
| 45 | + profile.depth = 1 |
| 46 | + |
| 47 | + |
| 48 | +def qos_profile_from_short_keys( |
| 49 | + preset_profile: str, reliability: str = None, durability: str = None, |
| 50 | + depth: Optional[int] = None, history: str = None, |
| 51 | +) -> rclpy.qos.QoSProfile: |
| 52 | + """Construct a QoSProfile given the name of a preset, and optional overrides.""" |
| 53 | + # Build a QoS profile based on user-supplied arguments |
| 54 | + profile = rclpy.qos.QoSPresetProfiles.get_from_short_key(preset_profile) |
| 55 | + profile_configure_short_keys(profile, reliability, durability, depth, history) |
| 56 | + return profile |
| 57 | + |
| 58 | + |
| 59 | +def add_qos_arguments(parser: ArgumentParser, default_profile_str: str): |
| 60 | + parser.add_argument( |
| 61 | + '--qos-profile', |
| 62 | + choices=rclpy.qos.QoSPresetProfiles.short_keys(), |
| 63 | + default=default_profile_str, |
| 64 | + help='Quality of service preset profile to subscribe with (default: {})' |
| 65 | + .format(default_profile_str)) |
| 66 | + default_profile = rclpy.qos.QoSPresetProfiles.get_from_short_key(default_profile_str) |
| 67 | + parser.add_argument( |
| 68 | + '--qos-depth', metavar='N', type=int, |
| 69 | + help='Queue size setting to subscribe with ' |
| 70 | + '(overrides depth value of --qos-profile option)') |
| 71 | + parser.add_argument( |
| 72 | + '--qos-history', |
| 73 | + choices=rclpy.qos.QoSHistoryPolicy.short_keys(), |
| 74 | + help='History of samples setting to subscribe with ' |
| 75 | + '(overrides history value of --qos-profile option, default: {})' |
| 76 | + .format(default_profile.history.short_key)) |
| 77 | + parser.add_argument( |
| 78 | + '--qos-reliability', |
| 79 | + choices=rclpy.qos.QoSReliabilityPolicy.short_keys(), |
| 80 | + help='Quality of service reliability setting to subscribe with ' |
| 81 | + '(overrides reliability value of --qos-profile option, default: ' |
| 82 | + 'Automatically match existing publishers )') |
| 83 | + parser.add_argument( |
| 84 | + '--qos-durability', |
| 85 | + choices=rclpy.qos.QoSDurabilityPolicy.short_keys(), |
| 86 | + help='Quality of service durability setting to subscribe with ' |
| 87 | + '(overrides durability value of --qos-profile option, default: ' |
| 88 | + 'Automatically match existing publishers )') |
0 commit comments