Skip to content
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
15 changes: 5 additions & 10 deletions src/message_filters/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -39,11 +39,15 @@
import threading
import rclpy

import builtin_interfaces
from typing import Type, Union

from rclpy.clock import ROSClock
from rclpy.duration import Duration
from rclpy.logging import LoggingSeverity
from rclpty.node import Node
from rclpy.qos import QoSProfile
from rclpy.time import Time
from rclpy.type_support import MsgT


class SimpleFilter(object):
Expand Down Expand Up @@ -76,14 +80,6 @@ class Subscriber(SimpleFilter):
from a ROS 2 subscription through to the filters which have connected
to it.
"""
<<<<<<< HEAD
def __init__(self, *args, **kwargs):
SimpleFilter.__init__(self)
self.node = args[0]
self.topic = args[2]
kwargs.setdefault('qos_profile', 10)
self.sub = self.node.create_subscription(*args[1:], self.callback, **kwargs)
=======

def __init__(
self,
Expand Down Expand Up @@ -112,7 +108,6 @@ def __init__(
callback=self.callback,
qos_profile=qos_profile,
)
>>>>>>> c31a7a9 (Add simple filter tutorials (#226))

def callback(self, msg):
self.signalMessage(msg)
Expand Down