Skip to content

Commit

Permalink
Add parameter to change QoS on ros2 service call similar to `ros2 t…
Browse files Browse the repository at this point in the history
…opic pub`

Signed-off-by: Bastian <[email protected]>

[squash before merge] React on comments
  • Loading branch information
bastianhjaeger committed May 23, 2023
1 parent 86ae393 commit 3fe424c
Show file tree
Hide file tree
Showing 4 changed files with 50 additions and 32 deletions.
1 change: 1 addition & 0 deletions ros2service/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@

<depend>rclpy</depend>
<depend>ros2cli</depend>
<depend>ros2topic</depend>

<exec_depend>python3-yaml</exec_depend>
<exec_depend>rosidl_runtime_py</exec_depend>
Expand Down
18 changes: 15 additions & 3 deletions ros2service/ros2service/verb/call.py
Original file line number Diff line number Diff line change
Expand Up @@ -16,10 +16,12 @@
import time

import rclpy
from rclpy.qos import QoSPresetProfiles
from ros2cli.node import NODE_NAME_PREFIX
from ros2service.api import ServiceNameCompleter
from ros2service.api import ServicePrototypeCompleter
from ros2service.api import ServiceTypeCompleter
from ros2topic.api import profile_configure_short_keys, add_qos_arguments
from ros2service.verb import VerbExtension
from rosidl_runtime_py import set_message_fields
import yaml
Expand Down Expand Up @@ -49,17 +51,23 @@ def add_arguments(self, parser, cli_name):
parser.add_argument(
'-r', '--rate', metavar='N', type=float,
help='Repeat the call at a specific rate in Hz')
add_qos_arguments(parser, 'services_default')

def main(self, *, args):
if args.rate is not None and args.rate <= 0:
raise RuntimeError('rate must be greater than zero')
period = 1. / args.rate if args.rate else None

default_profile = QoSPresetProfiles.get_from_short_key(args.qos_profile)
profile_configure_short_keys(
default_profile, args.qos_reliability, args.qos_durability,
args.qos_depth, args.qos_history)

return requester(
args.service_type, args.service_name, args.values, period)
args.service_type, args.service_name, args.values, period, default_profile)


def requester(service_type, service_name, values, period):
def requester(service_type, service_name, values, period, qos_profile):
# TODO(wjwwood) this logic should come from a rosidl related package
try:
parts = service_type.split('/')
Expand All @@ -83,7 +91,11 @@ def requester(service_type, service_name, values, period):

node = rclpy.create_node(NODE_NAME_PREFIX + '_requester_%s_%s' % (package_name, srv_name))

cli = node.create_client(srv_module, service_name)
cli = node.create_client(
srv_type=srv_module,
srv_name=service_name,
qos_profile=qos_profile
)

request = srv_module.Request()

Expand Down
32 changes: 32 additions & 0 deletions ros2topic/ros2topic/api/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -185,3 +185,35 @@ def qos_profile_from_short_keys(
profile = rclpy.qos.QoSPresetProfiles.get_from_short_key(preset_profile)
profile_configure_short_keys(profile, reliability, durability, depth, history)
return profile


def add_qos_arguments(parser, default_profile_str):
parser.add_argument(
'--qos-profile',
choices=rclpy.qos.QoSPresetProfiles.short_keys(),
default=default_profile_str,
help='Quality of service preset profile to subscribe with (default: {})'
.format(default_profile_str))
default_profile = rclpy.qos.QoSPresetProfiles.get_from_short_key(default_profile_str)
parser.add_argument(
'--qos-depth', metavar='N', type=int,
help='Queue size setting to subscribe with '
'(overrides depth value of --qos-profile option)')
parser.add_argument(
'--qos-history',
choices=rclpy.qos.QoSHistoryPolicy.short_keys(),
help='History of samples setting to subscribe with '
'(overrides history value of --qos-profile option, default: {})'
.format(default_profile.history.short_key))
parser.add_argument(
'--qos-reliability',
choices=rclpy.qos.QoSReliabilityPolicy.short_keys(),
help='Quality of service reliability setting to subscribe with '
'(overrides reliability value of --qos-profile option, default: '
'Automatically match existing publishers )')
parser.add_argument(
'--qos-durability',
choices=rclpy.qos.QoSDurabilityPolicy.short_keys(),
help='Quality of service durability setting to subscribe with '
'(overrides durability value of --qos-profile option, default: '
'Automatically match existing publishers )')
31 changes: 2 additions & 29 deletions ros2topic/ros2topic/verb/echo.py
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@
from ros2cli.node.strategy import add_arguments as add_strategy_node_arguments
from ros2cli.node.strategy import NodeStrategy
from ros2topic.api import get_msg_class
from ros2topic.api import qos_profile_from_short_keys
from ros2topic.api import qos_profile_from_short_keys, add_qos_arguments
from ros2topic.api import TopicNameCompleter
from ros2topic.api import unsigned_int
from ros2topic.verb import VerbExtension
Expand All @@ -55,34 +55,7 @@ def add_arguments(self, parser, cli_name):
parser.add_argument(
'message_type', nargs='?',
help="Type of the ROS message (e.g. 'std_msgs/msg/String')")
parser.add_argument(
'--qos-profile',
choices=rclpy.qos.QoSPresetProfiles.short_keys(),
help='Quality of service preset profile to subscribe with (default: {})'
.format(default_profile_str))
default_profile = rclpy.qos.QoSPresetProfiles.get_from_short_key(default_profile_str)
parser.add_argument(
'--qos-depth', metavar='N', type=int,
help='Queue size setting to subscribe with '
'(overrides depth value of --qos-profile option)')
parser.add_argument(
'--qos-history',
choices=rclpy.qos.QoSHistoryPolicy.short_keys(),
help='History of samples setting to subscribe with '
'(overrides history value of --qos-profile option, default: {})'
.format(default_profile.history.short_key))
parser.add_argument(
'--qos-reliability',
choices=rclpy.qos.QoSReliabilityPolicy.short_keys(),
help='Quality of service reliability setting to subscribe with '
'(overrides reliability value of --qos-profile option, default: '
'Automatically match existing publishers )')
parser.add_argument(
'--qos-durability',
choices=rclpy.qos.QoSDurabilityPolicy.short_keys(),
help='Quality of service durability setting to subscribe with '
'(overrides durability value of --qos-profile option, default: '
'Automatically match existing publishers )')
add_qos_arguments(parser, default_profile_str)
parser.add_argument(
'--csv', action='store_true',
help='Output all recursive fields separated by commas (e.g. for '
Expand Down

0 comments on commit 3fe424c

Please sign in to comment.