Skip to content

Commit 27f2102

Browse files
artivisivanpauno
authored andcommitted
Add action send_goal prototype completer (#301)
Signed-off-by: artivis <[email protected]>
1 parent f8afbed commit 27f2102

File tree

2 files changed

+16
-1
lines changed

2 files changed

+16
-1
lines changed

ros2action/ros2action/api/__init__.py

Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,8 @@
2222
from rclpy.expand_topic_name import expand_topic_name
2323
from rclpy.validate_full_topic_name import validate_full_topic_name
2424
from ros2cli.node.direct import DirectNode
25+
from rosidl_runtime_py.convert import message_to_yaml
26+
from rosidl_runtime_py.utilities import get_action
2527

2628

2729
def _is_action_status_topic(topic_name, action_name):
@@ -139,3 +141,14 @@ def __call__(self, prefix, parsed_args, **kwargs):
139141
if n == action_name:
140142
return t
141143
return []
144+
145+
146+
class ActionGoalPrototypeCompleter:
147+
"""Callable returning an action goal prototype."""
148+
149+
def __init__(self, *, action_type_key=None):
150+
self.action_type_key = action_type_key
151+
152+
def __call__(self, prefix, parsed_args, **kwargs):
153+
action = get_action(getattr(parsed_args, self.action_type_key))
154+
return [message_to_yaml(action.Goal())]

ros2action/ros2action/verb/send_goal.py

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@
1818
import rclpy
1919
from rclpy.action import ActionClient
2020
from ros2action.api import action_name_completer
21+
from ros2action.api import ActionGoalPrototypeCompleter
2122
from ros2action.api import ActionTypeCompleter
2223
from ros2action.verb import VerbExtension
2324
from ros2cli.node import NODE_NAME_PREFIX
@@ -39,9 +40,10 @@ def add_arguments(self, parser, cli_name):
3940
'action_type',
4041
help="Type of the ROS action (e.g. 'example_interfaces/action/Fibonacci')")
4142
arg.completer = ActionTypeCompleter(action_name_key='action_name')
42-
parser.add_argument(
43+
arg = parser.add_argument(
4344
'goal',
4445
help="Goal request values in YAML format (e.g. '{order: 10}')")
46+
arg.completer = ActionGoalPrototypeCompleter(action_type_key='action_type')
4547
parser.add_argument(
4648
'-f', '--feedback', action='store_true',
4749
help='Echo feedback messages for the goal')

0 commit comments

Comments
 (0)