1616import time
1717
1818import rclpy
19- from rclpy .qos import QoSDurabilityPolicy
20- from rclpy .qos import QoSProfile
21- from rclpy .qos import QoSReliabilityPolicy
19+ from rclpy .qos import QoSPresetProfiles
2220from ros2cli .node import NODE_NAME_PREFIX
2321from ros2service .api import ServiceNameCompleter
2422from ros2service .api import ServicePrototypeCompleter
2523from ros2service .api import ServiceTypeCompleter
24+ from ros2topic .api import profile_configure_short_keys , add_qos_arguments
2625from ros2service .verb import VerbExtension
27- from ros2service .api import profile_configure_short_keys
2826from rosidl_runtime_py import set_message_fields
2927import yaml
3028
3129
32- def get_pub_qos_profile ():
33- return QoSProfile (
34- reliability = QoSReliabilityPolicy .RELIABLE ,
35- durability = QoSDurabilityPolicy .TRANSIENT_LOCAL ,
36- depth = 1 )
37-
38-
3930class CallVerb (VerbExtension ):
4031 """Call a service."""
4132
@@ -60,50 +51,20 @@ def add_arguments(self, parser, cli_name):
6051 parser .add_argument (
6152 '-r' , '--rate' , metavar = 'N' , type = float ,
6253 help = 'Repeat the call at a specific rate in Hz' )
63- parser .add_argument (
64- '--qos-profile' ,
65- choices = rclpy .qos .QoSPresetProfiles .short_keys (),
66- help = 'Quality of service preset profile to publish)' )
67- default_profile = get_pub_qos_profile ()
68- parser .add_argument (
69- '--qos-depth' , metavar = 'N' , type = int , default = - 1 ,
70- help = 'Queue size setting to publish with '
71- '(overrides depth value of --qos-profile option)' )
72- parser .add_argument (
73- '--qos-history' ,
74- choices = rclpy .qos .QoSHistoryPolicy .short_keys (),
75- help = 'History of samples setting to publish with '
76- '(overrides history value of --qos-profile option, default: {})'
77- .format (default_profile .history .short_key ))
78- parser .add_argument (
79- '--qos-reliability' ,
80- choices = rclpy .qos .QoSReliabilityPolicy .short_keys (),
81- help = 'Quality of service reliability setting to publish with '
82- '(overrides reliability value of --qos-profile option, default: {})'
83- .format (default_profile .reliability .short_key ))
84- parser .add_argument (
85- '--qos-durability' ,
86- choices = rclpy .qos .QoSDurabilityPolicy .short_keys (),
87- help = 'Quality of service durability setting to publish with '
88- '(overrides durability value of --qos-profile option, default: {})'
89- .format (default_profile .durability .short_key ))
54+ add_qos_arguments (parser , 'services_default' )
9055
9156 def main (self , * , args ):
9257 if args .rate is not None and args .rate <= 0 :
9358 raise RuntimeError ('rate must be greater than zero' )
9459 period = 1. / args .rate if args .rate else None
9560
96- qos_profile = get_pub_qos_profile ()
97-
98- qos_profile_name = args .qos_profile
99- if qos_profile_name :
100- qos_profile = rclpy .qos .QoSPresetProfiles .get_from_short_key (qos_profile_name )
61+ default_profile = QoSPresetProfiles .get_from_short_key (args .qos_profile )
10162 profile_configure_short_keys (
102- qos_profile , args .qos_reliability , args .qos_durability ,
63+ default_profile , args .qos_reliability , args .qos_durability ,
10364 args .qos_depth , args .qos_history )
10465
10566 return requester (
106- args .service_type , args .service_name , args .values , period , qos_profile )
67+ args .service_type , args .service_name , args .values , period , default_profile )
10768
10869
10970def requester (service_type , service_name , values , period , qos_profile ):
0 commit comments