Skip to content

Commit

Permalink
[ros2topic bw] Monotonic clock, units, fstring (#455)
Browse files Browse the repository at this point in the history
* Use monotonic clock to avoid system time jumps

Signed-off-by: Shane Loretz <[email protected]>

* Fix units on message sizes

Signed-off-by: Shane Loretz <[email protected]>

* Make bw message easier to understand

Signed-off-by: Shane Loretz <[email protected]>

* Use f strings

Signed-off-by: Shane Loretz <[email protected]>

* Add back []

Signed-off-by: Shane Loretz <[email protected]>

* Update BW test regex

Signed-off-by: Shane Loretz <[email protected]>
  • Loading branch information
sloretz authored Apr 17, 2020
1 parent 8a73f34 commit e1fa7d1
Show file tree
Hide file tree
Showing 2 changed files with 26 additions and 16 deletions.
35 changes: 24 additions & 11 deletions ros2topic/ros2topic/verb/bw.py
Original file line number Diff line number Diff line change
Expand Up @@ -58,6 +58,18 @@ def positive_int(string):
return value


def str_bytes(num_bytes):
return f'{num_bytes:.0f} B'


def str_kilobytes(num_bytes):
return f'{num_bytes/1000:.2f} KB'


def str_megabytes(num_bytes):
return f'{num_bytes/1000/1000:.2f} MB'


class BwVerb(VerbExtension):
"""Display bandwidth used by topic."""

Expand All @@ -69,8 +81,8 @@ def add_arguments(self, parser, cli_name):
include_hidden_topics_key='include_hidden_topics')
parser.add_argument(
'--window', '-w', type=positive_int, default=DEFAULT_WINDOW_SIZE,
help='window size, in # of messages, for calculating rate '
'(default: %d)' % DEFAULT_WINDOW_SIZE, metavar='WINDOW')
help='maximum window size, in # of messages, for calculating rate '
f'(default: {DEFAULT_WINDOW_SIZE})', metavar='WINDOW')

def main(self, *, args):
with DirectNode(args) as node:
Expand All @@ -90,7 +102,7 @@ def callback(self, data):
"""Execute ros sub callback."""
with self.lock:
try:
t = time.time()
t = time.monotonic()
self.times.append(t)
# TODO(yechun1): Subscribing to the msgs and calculate the length may be
# inefficiency. To optimize here if found better solution.
Expand All @@ -109,7 +121,7 @@ def print_bw(self):
return
with self.lock:
n = len(self.times)
tn = time.time()
tn = time.monotonic()
t0 = self.times[0]

total = sum(self.sizes)
Expand All @@ -123,15 +135,16 @@ def print_bw(self):
# min/max and even mean are likely to be much smaller,
# but for now I prefer unit consistency
if bytes_per_s < 1000:
bw, mean, min_s, max_s = ['%.2fB/s' % v for v in [bytes_per_s, mean, min_s, max_s]]
bw, mean, min_s, max_s = map(str_bytes, (bytes_per_s, mean, min_s, max_s))
elif bytes_per_s < 1000000:
bw, mean, min_s, max_s = \
['%.2fKB/s' % (v / 1000) for v in [bytes_per_s, mean, min_s, max_s]]
bw, mean, min_s, max_s = map(str_kilobytes, (bytes_per_s, mean, min_s, max_s))
else:
bw, mean, min_s, max_s = \
['%.2fMB/s' % (v / 1000000) for v in [bytes_per_s, mean, min_s, max_s]]
bw, mean, min_s, max_s = map(str_megabytes, (bytes_per_s, mean, min_s, max_s))

# Bandwidth is per second
bw += '/s'

print('average: %s\n\tmean: %s min: %s max: %s window: %s' % (bw, mean, min_s, max_s, n))
print(f'{bw} from {n} messages\n\tMessage size mean: {mean} min: {min_s} max: {max_s}')


def _rostopic_bw(node, topic, window_size=DEFAULT_WINDOW_SIZE):
Expand All @@ -151,7 +164,7 @@ def _rostopic_bw(node, topic, window_size=DEFAULT_WINDOW_SIZE):
raw=True
)

print('Subscribed to [%s]' % topic)
print(f'Subscribed to [{topic}]')
timer = node.create_timer(1, rt.print_bw)
while rclpy.ok():
rclpy.spin_once(node)
Expand Down
7 changes: 2 additions & 5 deletions ros2topic/test/test_cli.py
Original file line number Diff line number Diff line change
Expand Up @@ -678,11 +678,8 @@ def test_topic_bw(self):
assert topic_command.wait_for_output(functools.partial(
launch_testing.tools.expect_output, expected_lines=[
'Subscribed to [/defaults]',
re.compile(r'average: \d{2}\.\d{2}B/s'),
re.compile(
r'\s*mean: \d{2}\.\d{2}B/s min: \d{2}\.\d{2}B/s'
r' max: \d{2}\.\d{2}B/s window: \d+'
)
re.compile(r'\d{2} B/s from \d+ messages'),
re.compile(r'\s*Message size mean: \d{2} B min: \d{2} B max: \d{2} B')
], strict=True
), timeout=10)
assert topic_command.wait_for_shutdown(timeout=10)

0 comments on commit e1fa7d1

Please sign in to comment.