diff --git a/doc/jsk_topic_tools/scripts/synchronize_republish.rst b/doc/jsk_topic_tools/scripts/synchronize_republish.rst index 5900edd61..81ef3b047 100644 --- a/doc/jsk_topic_tools/scripts/synchronize_republish.rst +++ b/doc/jsk_topic_tools/scripts/synchronize_republish.rst @@ -35,6 +35,10 @@ Parameters If ``true``, approximate synchronization is used for synchoronizing assigned topics. +* ``~allow_headerless`` (Bool, Default: ``false``) + + If ``true``, ``allow_headerless`` option of approximate synchronization is enabled. + * ``~queue_size`` (Integer, Default: ``100``) Queue length for subscribing topics. diff --git a/jsk_data/src/jsk_data/download_data.py b/jsk_data/src/jsk_data/download_data.py index 2bd7bca6c..e3dc4f211 100644 --- a/jsk_data/src/jsk_data/download_data.py +++ b/jsk_data/src/jsk_data/download_data.py @@ -31,6 +31,8 @@ def extract_file(path, to_directory='.', chmod=True): opener, mode, getnames = zipfile.ZipFile, 'r', lambda f: f.namelist() elif path.endswith('.tar.gz') or path.endswith('.tgz'): opener, mode, getnames = tarfile.open, 'r:gz', lambda f: f.getnames() + elif path.endswith('.tar.xz'): + opener, mode, getnames = tarfile.open, 'r:xz', lambda f: f.getnames() elif path.endswith('.tar.bz2') or path.endswith('.tbz'): opener, mode, getnames = tarfile.open, 'r:bz2', lambda f: f.getnames() else: diff --git a/jsk_topic_tools/scripts/synchronize_republish.py b/jsk_topic_tools/scripts/synchronize_republish.py index 3da1959ce..96e6a5ed4 100755 --- a/jsk_topic_tools/scripts/synchronize_republish.py +++ b/jsk_topic_tools/scripts/synchronize_republish.py @@ -9,10 +9,13 @@ def callback(*msgs): stamp = None for msg, pub in zip(msgs, pubs): - if stamp is None: - stamp = msg.header.stamp - else: - msg.header.stamp = stamp + try: + if stamp is None: + stamp = msg.header.stamp + else: + msg.header.stamp = stamp + except AttributeError: + pass pub.publish(msg) @@ -20,6 +23,7 @@ def callback(*msgs): rospy.init_node('synchrnoze_republish') topics = rospy.get_param('~topics') use_async = rospy.get_param('~approximate_sync', False) + allow_headerless = rospy.get_param('~allow_headerless', False) queue_size = rospy.get_param('~queue_size', 100) slop = rospy.get_param('~slop', 0.1) pubs = [] @@ -34,7 +38,7 @@ def callback(*msgs): subs.append(sub) if use_async: sync = message_filters.ApproximateTimeSynchronizer( - subs, queue_size=queue_size, slop=slop) + subs, queue_size=queue_size, slop=slop, allow_headerless=allow_headerless) else: sync = message_filters.TimeSynchronizer(subs, queue_size=queue_size) sync.registerCallback(callback)