Skip to content

Commit

Permalink
[jsk_topic_tools] Add reset arg to rospy.Timer for rosbag play --loop
Browse files Browse the repository at this point in the history
  • Loading branch information
nakane11 committed Dec 15, 2023
1 parent 7cca4cb commit aa3aad3
Showing 1 changed file with 13 additions and 1 deletion.
14 changes: 13 additions & 1 deletion jsk_topic_tools/scripts/boolean_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,8 @@
import sys

import rospy
from distutils.version import LooseVersion
import pkg_resources
import std_msgs.msg

from jsk_topic_tools.eval_utils import expr_eval
Expand Down Expand Up @@ -65,7 +67,17 @@ def __init__(self):
if rate == 0:
rospy.logwarn('You cannot set 0 as the rate; change it to 100.')
rate = 100
rospy.Timer(rospy.Duration(1.0 / rate), self.timer_cb)
kwargs = dict(
period=rospy.Duration(1.0 / rate),
callback=self.timer_cb,
oneshot=False,
)
if (LooseVersion(pkg_resources.get_distribution('rospy').version) >=
LooseVersion('1.12.0')) and rospy.get_param('/use_sim_time', None):
# on >=kinetic, it raises ROSTimeMovedBackwardsException
# when we use rosbag play --loop.
kwargs['reset'] = True
rospy.Timer(**kwargs)

def callback(self, topic_name, msg):
if isinstance(msg, rospy.msg.AnyMsg):
Expand Down

0 comments on commit aa3aad3

Please sign in to comment.