def add_arguments(self, parser, cli_name): arg = parser.add_argument( 'service_name', help="Name of the ROS service to call to (e.g. '/add_two_ints')") arg.completer = ServiceNameCompleter( include_hidden_services_key='include_hidden_services') arg = parser.add_argument( 'service_type', help="Type of the ROS service (e.g. 'std_srvs/srv/Empty')") arg.completer = ServiceTypeCompleter(service_name_key='service_name') arg = parser.add_argument( 'values', nargs='?', default='{}', help='Values to fill the service request with in YAML format ' + "(e.g. '{a: 1, b: 2}'), " + 'otherwise the service request will be published with default values' ) arg.completer = ServicePrototypeCompleter( service_type_key='service_type') parser.add_argument('-r', '--rate', metavar='N', type=float, help='Repeat the call at a specific rate in Hz')
def add_arguments(self, parser, cli_name): arg = parser.add_argument( 'service_name', help= "Name of the ROS service to get type (e.g. '/talker/list_parameters')" ) arg.completer = ServiceNameCompleter( include_hidden_services_key='include_hidden_services')