Skip to content

Commit f27a29f

Browse files
committed
Add tui (interactive mode) for message creation
Signed-off-by: Florian Vahl <[email protected]>
1 parent 409bfdf commit f27a29f

File tree

2 files changed

+165
-21
lines changed

2 files changed

+165
-21
lines changed

ros2topic/package.xml

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,8 @@
2020
<depend>ros2cli</depend>
2121

2222
<exec_depend>python3-numpy</exec_depend>
23+
<exec_depend>python3-prompt-toolkit</exec_depend>
24+
<exec_depend>python3-pygments</exec_depend>
2325
<exec_depend>python3-yaml</exec_depend>
2426
<exec_depend>rclpy</exec_depend>
2527
<exec_depend>rosidl_runtime_py</exec_depend>

ros2topic/ros2topic/verb/pub.py

Lines changed: 163 additions & 21 deletions
Original file line numberDiff line numberDiff line change
@@ -12,10 +12,18 @@
1212
# See the License for the specific language governing permissions and
1313
# limitations under the License.
1414

15+
import hashlib
16+
import os
17+
import tempfile
1518
import time
1619
from typing import Optional
1720
from typing import TypeVar
1821

22+
from prompt_toolkit import prompt
23+
from prompt_toolkit.formatted_text import HTML
24+
from prompt_toolkit.key_binding import KeyBindings
25+
from prompt_toolkit.lexers import PygmentsLexer
26+
from pygments.lexers.data import YamlLexer
1927
import rclpy
2028
from rclpy.node import Node
2129
from rclpy.qos import QoSDurabilityPolicy
@@ -28,6 +36,7 @@
2836
from ros2topic.api import TopicTypeCompleter
2937
from ros2topic.verb import VerbExtension
3038
from rosidl_runtime_py import set_message_fields
39+
from rosidl_runtime_py.convert import message_to_yaml
3140
from rosidl_runtime_py.utilities import get_message
3241
import yaml
3342

@@ -84,6 +93,9 @@ def add_arguments(self, parser, cli_name):
8493
parser.add_argument(
8594
'-p', '--print', metavar='N', type=int, default=1,
8695
help='Only print every N-th published message (default: 1)')
96+
parser.add_argument(
97+
'-i', '--interactive', action='store_true',
98+
help='Interactively edit and send the message')
8799
group = parser.add_mutually_exclusive_group()
88100
group.add_argument(
89101
'-1', '--once', action='store_true',
@@ -135,7 +147,7 @@ def main(self, *, args):
135147
return main(args)
136148

137149

138-
def main(args):
150+
def main(args) -> Optional[str]:
139151
qos_profile = get_pub_qos_profile()
140152

141153
qos_profile_name = args.qos_profile
@@ -149,12 +161,29 @@ def main(args):
149161
if args.once:
150162
times = 1
151163

164+
if args.interactive:
165+
print('Interactive mode...')
166+
# Read last message that was send if it exists in temp
167+
content = get_last_message_content(args.message_type)
168+
# Show the tui
169+
content = show_interactive_tui(
170+
message_to_yaml(parse_msg(args.message_type, content)),
171+
message_to_yaml(parse_msg(args.message_type)))
172+
# Load msg YAML just to be sure it does not fail and we store a broken message
173+
parse_msg(args.message_type, content)
174+
# Store the user input so we are able to load it the next time
175+
store_message_content(args.message_type, content)
176+
else:
177+
content = args.values
178+
179+
# Parse the yaml string and get a message ofbject of the desired type
180+
msg = parse_msg(args.message_type, content)
181+
152182
with DirectNode(args, node_name=args.node_name) as node:
153183
return publisher(
154184
node.node,
155-
args.message_type,
156185
args.topic_name,
157-
args.values,
186+
msg,
158187
1. / args.rate,
159188
args.print,
160189
times,
@@ -164,28 +193,147 @@ def main(args):
164193
args.keep_alive)
165194

166195

196+
def get_history_file(msg_type: str) -> str:
197+
"""
198+
Get paths for semi persistent history based on message name.
199+
200+
:param msg_type: Name of the message type
201+
:returns: The path where a history file would be located if it exists
202+
"""
203+
# Get temporary directory name
204+
msg_history_cache_folder_path = os.path.join(
205+
tempfile.gettempdir(), "ros_interactive_msg_cache")
206+
# Create temporary history dir if needed
207+
os.makedirs(msg_history_cache_folder_path, exist_ok=True)
208+
# Create a file based on the message name
209+
return os.path.join(
210+
msg_history_cache_folder_path,
211+
f'{hashlib.sha224(msg_type.encode()).hexdigest()[:20]}.yaml')
212+
213+
214+
def get_last_message_content(msg_type: str) -> str:
215+
"""
216+
Retrive the last message of the given type that was send using the tui if it exists.
217+
218+
:param msg_type: Name of the message type
219+
:returns: The YAML representation containing the last message or an empty dict
220+
"""
221+
content = "{}"
222+
try:
223+
history_path = get_history_file(msg_type)
224+
# Load previous values for that message type
225+
if os.path.exists(history_path):
226+
with open(history_path, 'r') as f:
227+
content = f.read()
228+
except OSError:
229+
print('Unable load history...')
230+
return content
231+
232+
233+
def store_message_content(msg_type: str, content: str) -> None:
234+
"""
235+
Store the YAML for the current message in a semi persistent file.
236+
237+
:param msg_type: Name of the message type
238+
:param content: The YAML entered by the user
239+
"""
240+
try:
241+
history_path = get_history_file(msg_type)
242+
# Clear cache
243+
if os.path.exists(history_path):
244+
os.remove(history_path)
245+
# Store last message in cache
246+
with open(history_path, 'w') as f:
247+
f.write(content)
248+
except OSError:
249+
print('Unable to store history')
250+
251+
252+
def show_interactive_tui(msg_str: str, default_msg_str: Optional[str] = None) -> str:
253+
"""
254+
Show a tui to edit a given message yaml.
255+
256+
:param msg_str: Mesage yaml string which is initially presented to the user
257+
:param default_msg_str: Mesage yaml string with default values for the given message
258+
:return: The mesage yaml string edited by the user
259+
"""
260+
# Create the bottom bar to pressent the options to the user
261+
def bottom_toolbar():
262+
return HTML(' Continue: <b>alt+enter</b> | Exit: <b>ctrl+c</b> | Reset: <b>ctrl+r</b>')
263+
264+
# Create key bindings for the prompt
265+
bindings = KeyBindings()
266+
if default_msg_str is not None:
267+
@bindings.add('c-r')
268+
def _(event):
269+
"""Reset the promt to the default message."""
270+
event.app.current_buffer.text = default_msg_str
271+
272+
# Show prompt to edit the message before sending it
273+
return prompt(
274+
"> ",
275+
multiline=True,
276+
default=msg_str,
277+
lexer=PygmentsLexer(YamlLexer),
278+
mouse_support=True,
279+
bottom_toolbar=bottom_toolbar,
280+
key_bindings=bindings)
281+
282+
283+
def parse_msg(msg_type: str, yaml_values: Optional[str] = None) -> MsgType:
284+
"""
285+
Parse the name and contents of a given message.
286+
287+
:param msg_type: Name of the message as a string (e.g. std_msgs/msg/Header)
288+
:param yaml_values: Contents of the message as a string in YAML layout
289+
:returns: An constructed instance of the message type
290+
"""
291+
# Get the message type from the name string
292+
try:
293+
msg_module = get_message(msg_type)
294+
except (AttributeError, ModuleNotFoundError, ValueError):
295+
raise RuntimeError('The passed message type is invalid')
296+
# Create a default instance of the message with the given name
297+
msg = msg_module()
298+
# Check if we want to add values to the message
299+
if yaml_values is not None:
300+
# Load the user provided fields of the message
301+
values_dictionary = yaml.safe_load(yaml_values)
302+
if not isinstance(values_dictionary, dict):
303+
raise RuntimeError('The passed value needs to be a dictionary in YAML format')
304+
# Set all fields in the message to the provided values
305+
try:
306+
set_message_fields(msg, values_dictionary)
307+
except Exception as e:
308+
raise RuntimeError(f'Failed to populate field: {e}')
309+
return msg
310+
311+
167312
def publisher(
168313
node: Node,
169-
message_type: MsgType,
170314
topic_name: str,
171-
values: dict,
315+
msg: MsgType,
172316
period: float,
173317
print_nth: int,
174318
times: int,
175319
wait_matching_subscriptions: int,
176320
qos_profile: QoSProfile,
177321
keep_alive: float,
178-
) -> Optional[str]:
179-
"""Initialize a node with a single publisher and run its publish loop (maybe only once)."""
180-
try:
181-
msg_module = get_message(message_type)
182-
except (AttributeError, ModuleNotFoundError, ValueError):
183-
raise RuntimeError('The passed message type is invalid')
184-
values_dictionary = yaml.safe_load(values)
185-
if not isinstance(values_dictionary, dict):
186-
return 'The passed value needs to be a dictionary in YAML format'
322+
) -> None:
323+
"""
324+
Initialize a node with a single publisher and run its publish loop (maybe only once).
187325
188-
pub = node.create_publisher(msg_module, topic_name, qos_profile)
326+
:param node: The given node used for publishing the given message
327+
:param topic_name: The topic on which the the message is published
328+
:param msg: The message that is published
329+
:param period: Period after which the msg is published again
330+
:param print_nth: Interval in which the message is printed
331+
:param times: Number of times the message is published
332+
:param wait_matching_subscriptions: Wait until there is a certain number of subscribtions
333+
:param qos_profile: QOS profile
334+
:param keep_alive: Time the node is kept alive after the message was send
335+
"""
336+
pub = node.create_publisher(type(msg), topic_name, qos_profile)
189337

190338
times_since_last_log = 0
191339
while pub.get_subscription_count() < wait_matching_subscriptions:
@@ -196,12 +344,6 @@ def publisher(
196344
times_since_last_log = (times_since_last_log + 1) % 10
197345
time.sleep(0.1)
198346

199-
msg = msg_module()
200-
try:
201-
set_message_fields(msg, values_dictionary)
202-
except Exception as e:
203-
return 'Failed to populate field: {0}'.format(e)
204-
205347
print('publisher: beginning loop')
206348
count = 0
207349

0 commit comments

Comments
 (0)