Skip to content

Commit

Permalink
[ros2topic] use a timer instead of time.sleep
Browse files Browse the repository at this point in the history
time.sleep will add the time the publish call takes to each cycle. Use a timer to avoid pub rate loss.

Signed-off-by: Chris Ye <[email protected]>
  • Loading branch information
yechun1 committed Sep 1, 2018
1 parent 4dbd63b commit 2a20391
Showing 1 changed file with 12 additions and 5 deletions.
17 changes: 12 additions & 5 deletions ros2topic/ros2topic/verb/pub.py
Original file line number Diff line number Diff line change
Expand Up @@ -101,14 +101,21 @@ def publisher(

print('publisher: beginning loop')
count = 0
while rclpy.ok():

def timer_callback():
nonlocal count
count += 1
if print_nth and count % print_nth == 0:
print('publishing #%d: %r\n' % (count, msg))
pub.publish(msg)
if once:
time.sleep(0.1) # make sure the message reaches the wire before exiting
break
time.sleep(period)

timer = node.create_timer(period, timer_callback)
if once:
rclpy.spin_once(node)
time.sleep(0.1) # make sure the message reaches the wire before exiting
else:
rclpy.spin(node)

node.destroy_timer(timer)
node.destroy_node()
rclpy.shutdown()

0 comments on commit 2a20391

Please sign in to comment.