Skip to content

Commit

Permalink
Switch to meaningful names for the event_type.
Browse files Browse the repository at this point in the history
Signed-off-by: Chris Lalancette <[email protected]>
  • Loading branch information
clalancette committed May 19, 2023
1 parent 6458a8d commit ba9cedf
Show file tree
Hide file tree
Showing 2 changed files with 38 additions and 10 deletions.
40 changes: 34 additions & 6 deletions ros2service/ros2service/verb/echo.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,8 @@
# See the License for the specific language governing permissions and
# limitations under the License.

from collections import OrderedDict
import sys
from typing import TypeVar

import rclpy
Expand All @@ -24,20 +26,34 @@
from ros2service.api import ServiceTypeCompleter
from ros2service.verb import VerbExtension
from rosidl_runtime_py import message_to_csv
from rosidl_runtime_py import message_to_yaml
from rosidl_runtime_py import message_to_ordereddict
from rosidl_runtime_py.utilities import get_service
from service_msgs.msg import ServiceEventInfo

import yaml


DEFAULT_TRUNCATE_LENGTH = 128
MsgType = TypeVar('MsgType')


class EchoVerb(VerbExtension):
"""Echo a service."""

# Custom representer for getting clean YAML output that preserves the order in an OrderedDict.
# Inspired by: http://stackoverflow.com/a/16782282/7169408
def __represent_ordereddict(self, dumper, data):
items = []
for k, v in data.items():
items.append((dumper.represent_data(k), dumper.represent_data(v)))
return yaml.nodes.MappingNode(u'tag:yaml.org,2002:map', items)

def __init__(self):
self.event_type_map = [
(v, k) for k, v in ServiceEventInfo._Metaclass_ServiceEventInfo__constants.items()]
self._event_number_to_name = {}
for k, v in ServiceEventInfo._Metaclass_ServiceEventInfo__constants.items():
self._event_number_to_name[v] = k

yaml.add_representer(OrderedDict, self.__represent_ordereddict)

def add_arguments(self, parser, cli_name):
arg = parser.add_argument(
Expand Down Expand Up @@ -126,9 +142,21 @@ def _subscriber_callback(self, msg):
to_print = message_to_csv(msg, truncate_length=self.truncate_length,
no_arr=self.no_arr, no_str=self.no_str)
else:
to_print = message_to_yaml(msg, truncate_length=self.truncate_length,
no_arr=self.no_arr, no_str=self.no_str,
flow_style=self.flow_style)
# The "easy" way to print out a representation here is to call message_to_yaml().
# However, the message contains numbers for the event type, but we want to show
# meaningful names to the user. So we call message_to_ordereddict() instead,
# and replace the numbers with meaningful names before dumping to YAML.
msgdict = message_to_ordereddict(msg, truncate_length=self.truncate_length,
no_arr=self.no_arr, no_str=self.no_str)

if 'info' in msgdict:
info = msgdict['info']
if 'event_type' in info:
info['event_type'] = self._event_number_to_name[info['event_type']]

to_print = yaml.dump(msgdict, allow_unicode=True, width=sys.maxsize,
default_flow_style=self.flow_style)

to_print += '---'

print(to_print)
8 changes: 4 additions & 4 deletions ros2service/test/test_echo.py
Original file line number Diff line number Diff line change
Expand Up @@ -115,7 +115,7 @@ def test_echo_no_arr(self):
echo_arguments = ['echo', '/test_introspectable', '--no-arr']
expected_output = [
'info:',
' event_type: 0',
' event_type: REQUEST_SENT',
' stamp:',
re.compile(r' sec: \d+'),
re.compile(r' nanosec: \d+'),
Expand All @@ -125,7 +125,7 @@ def test_echo_no_arr(self):
"response: '<sequence type: test_msgs/srv/BasicTypes_Response[1], length: 0>'",
'---',
'info:',
' event_type: 1',
' event_type: REQUEST_RECEIVED',
' stamp:',
re.compile(r' sec: \d+'),
re.compile(r' nanosec: \d+'),
Expand All @@ -135,7 +135,7 @@ def test_echo_no_arr(self):
"response: '<sequence type: test_msgs/srv/BasicTypes_Response[1], length: 0>'",
'---',
'info:',
' event_type: 2',
' event_type: RESPONSE_SENT',
' stamp:',
re.compile(r' sec: \d+'),
re.compile(r' nanosec: \d+'),
Expand All @@ -145,7 +145,7 @@ def test_echo_no_arr(self):
"response: '<sequence type: test_msgs/srv/BasicTypes_Response[1], length: 1>'",
'---',
'info:',
' event_type: 3',
' event_type: RESPONSE_RECEIVED',
' stamp:',
re.compile(r' sec: \d+'),
re.compile(r' nanosec: \d+'),
Expand Down

0 comments on commit ba9cedf

Please sign in to comment.