Skip to content

Commit 351ef3c

Browse files
authored
Load a message/request/goal from standard input (#844)
* Load a message/request/goal from standard input Signed-off-by: ymd-stella <[email protected]>
1 parent 5dc0dda commit 351ef3c

File tree

4 files changed

+49
-7
lines changed

4 files changed

+49
-7
lines changed

ros2action/ros2action/verb/send_goal.py

Lines changed: 14 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@
1919
from ros2action.api import ActionGoalPrototypeCompleter
2020
from ros2action.api import ActionTypeCompleter
2121
from ros2action.verb import VerbExtension
22+
from ros2cli.helpers import collect_stdin
2223
from ros2cli.node import NODE_NAME_PREFIX
2324
from rosidl_runtime_py import message_to_yaml
2425
from rosidl_runtime_py import set_message_fields
@@ -39,9 +40,13 @@ 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-
arg = parser.add_argument(
43-
'goal',
43+
group = parser.add_mutually_exclusive_group()
44+
arg = group.add_argument(
45+
'goal', nargs='?', default='{}',
4446
help="Goal request values in YAML format (e.g. '{order: 10}')")
47+
group.add_argument(
48+
'--stdin', action='store_true',
49+
help='Read goal from standard input')
4550
arg.completer = ActionGoalPrototypeCompleter(action_type_key='action_type')
4651
parser.add_argument(
4752
'-f', '--feedback', action='store_true',
@@ -51,7 +56,13 @@ def main(self, *, args):
5156
feedback_callback = None
5257
if args.feedback:
5358
feedback_callback = _feedback_callback
54-
return send_goal(args.action_name, args.action_type, args.goal, feedback_callback)
59+
60+
if args.stdin:
61+
goal = collect_stdin()
62+
else:
63+
goal = args.goal
64+
65+
return send_goal(args.action_name, args.action_type, goal, feedback_callback)
5566

5667

5768
def _goal_status_to_string(status):

ros2cli/ros2cli/helpers.py

Lines changed: 11 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,7 @@
1616
import functools
1717
import inspect
1818
import os
19+
import sys
1920
import time
2021

2122

@@ -107,3 +108,13 @@ def unsigned_int(string):
107108
if value < 0:
108109
raise ArgumentTypeError('value must be non-negative integer')
109110
return value
111+
112+
113+
def collect_stdin():
114+
lines = b''
115+
while True:
116+
line = sys.stdin.buffer.readline()
117+
if not line:
118+
break
119+
lines += line
120+
return lines

ros2service/ros2service/verb/call.py

Lines changed: 12 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,7 @@
1616
import time
1717

1818
import rclpy
19+
from ros2cli.helpers import collect_stdin
1920
from ros2cli.node import NODE_NAME_PREFIX
2021
from ros2service.api import ServiceNameCompleter
2122
from ros2service.api import ServicePrototypeCompleter
@@ -39,13 +40,17 @@ def add_arguments(self, parser, cli_name):
3940
help="Type of the ROS service (e.g. 'std_srvs/srv/Empty')")
4041
arg.completer = ServiceTypeCompleter(
4142
service_name_key='service_name')
42-
arg = parser.add_argument(
43+
group = parser.add_mutually_exclusive_group()
44+
arg = group.add_argument(
4345
'values', nargs='?', default='{}',
4446
help='Values to fill the service request with in YAML format ' +
4547
"(e.g. '{a: 1, b: 2}'), " +
4648
'otherwise the service request will be published with default values')
4749
arg.completer = ServicePrototypeCompleter(
4850
service_type_key='service_type')
51+
group.add_argument(
52+
'--stdin', action='store_true',
53+
help='Read values from standard input')
4954
parser.add_argument(
5055
'-r', '--rate', metavar='N', type=float,
5156
help='Repeat the call at a specific rate in Hz')
@@ -55,8 +60,13 @@ def main(self, *, args):
5560
raise RuntimeError('rate must be greater than zero')
5661
period = 1. / args.rate if args.rate else None
5762

63+
if args.stdin:
64+
values = collect_stdin()
65+
else:
66+
values = args.values
67+
5868
return requester(
59-
args.service_type, args.service_name, args.values, period)
69+
args.service_type, args.service_name, values, period)
6070

6171

6272
def requester(service_type, service_name, values, period):

ros2topic/ros2topic/verb/pub.py

Lines changed: 12 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@
1919
import rclpy
2020
from rclpy.node import Node
2121
from rclpy.qos import QoSProfile
22+
from ros2cli.helpers import collect_stdin
2223
from ros2cli.node.direct import add_arguments as add_direct_node_arguments
2324
from ros2cli.node.direct import DirectNode
2425
from ros2topic.api import add_qos_arguments
@@ -58,13 +59,17 @@ def add_arguments(self, parser, cli_name):
5859
help="Type of the ROS message (e.g. 'std_msgs/String')")
5960
arg.completer = TopicTypeCompleter(
6061
topic_name_key='topic_name')
61-
arg = parser.add_argument(
62+
group = parser.add_mutually_exclusive_group()
63+
arg = group.add_argument(
6264
'values', nargs='?', default='{}',
6365
help='Values to fill the message with in YAML format '
6466
"(e.g. 'data: Hello World'), "
6567
'otherwise the message will be published with default values')
6668
arg.completer = TopicMessagePrototypeCompleter(
6769
topic_type_key='message_type')
70+
group.add_argument(
71+
'--stdin', action='store_true',
72+
help='Read values from standard input')
6873
parser.add_argument(
6974
'-r', '--rate', metavar='N', type=positive_float, default=1.0,
7075
help='Publishing rate in Hz (default: 1)')
@@ -115,12 +120,17 @@ def main(args):
115120
if args.once:
116121
times = 1
117122

123+
if args.stdin:
124+
values = collect_stdin()
125+
else:
126+
values = args.values
127+
118128
with DirectNode(args, node_name=args.node_name) as node:
119129
return publisher(
120130
node.node,
121131
args.message_type,
122132
args.topic_name,
123-
args.values,
133+
values,
124134
1. / args.rate,
125135
args.print,
126136
times,

0 commit comments

Comments
 (0)