From 1eeba50c28f78ff2cd584a155fb2ac5058dde5fb Mon Sep 17 00:00:00 2001 From: artivis Date: Wed, 17 Jul 2019 11:04:32 -0400 Subject: [PATCH] add action send_goal prototype completer Signed-off-by: artivis --- ros2action/ros2action/api/__init__.py | 13 +++++++++++++ ros2action/ros2action/verb/send_goal.py | 4 +++- 2 files changed, 16 insertions(+), 1 deletion(-) diff --git a/ros2action/ros2action/api/__init__.py b/ros2action/ros2action/api/__init__.py index 7f1aba7df..303fccef1 100644 --- a/ros2action/ros2action/api/__init__.py +++ b/ros2action/ros2action/api/__init__.py @@ -22,6 +22,8 @@ from rclpy.expand_topic_name import expand_topic_name from rclpy.validate_full_topic_name import validate_full_topic_name from ros2cli.node.direct import DirectNode +from rosidl_runtime_py.convert import message_to_yaml +from rosidl_runtime_py.utilities import get_action def _is_action_status_topic(topic_name, action_name): @@ -139,3 +141,14 @@ def __call__(self, prefix, parsed_args, **kwargs): if n == action_name: return t return [] + + +class ActionGoalPrototypeCompleter: + """Callable returning an action goal prototype.""" + + def __init__(self, *, action_type_key=None): + self.action_type_key = action_type_key + + def __call__(self, prefix, parsed_args, **kwargs): + action = get_action(getattr(parsed_args, self.action_type_key)) + return [message_to_yaml(action.Goal())] diff --git a/ros2action/ros2action/verb/send_goal.py b/ros2action/ros2action/verb/send_goal.py index 5da03cd10..19a8bc968 100644 --- a/ros2action/ros2action/verb/send_goal.py +++ b/ros2action/ros2action/verb/send_goal.py @@ -18,6 +18,7 @@ import rclpy from rclpy.action import ActionClient from ros2action.api import action_name_completer +from ros2action.api import ActionGoalPrototypeCompleter from ros2action.api import ActionTypeCompleter from ros2action.verb import VerbExtension from ros2cli.node import NODE_NAME_PREFIX @@ -39,9 +40,10 @@ def add_arguments(self, parser, cli_name): 'action_type', help="Type of the ROS action (e.g. 'example_interfaces/action/Fibonacci')") arg.completer = ActionTypeCompleter(action_name_key='action_name') - parser.add_argument( + arg = parser.add_argument( 'goal', help="Goal request values in YAML format (e.g. '{order: 10}')") + arg.completer = ActionGoalPrototypeCompleter(action_type_key='action_type') parser.add_argument( '-f', '--feedback', action='store_true', help='Echo feedback messages for the goal')