Skip to content

Commit

Permalink
Durability policy for publisher in speckle filter test
Browse files Browse the repository at this point in the history
  • Loading branch information
berend-kupers committed Aug 19, 2024
1 parent 4440285 commit e02d296
Showing 1 changed file with 3 additions and 1 deletion.
4 changes: 3 additions & 1 deletion test/test_speckle_filter.test.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
import pytest
import rclpy
from rclpy.node import Node
from rclpy.qos import QoSProfile, QoSDurabilityPolicy
from sensor_msgs.msg import LaserScan


Expand Down Expand Up @@ -91,7 +92,8 @@ def __init__(self):
super().__init__("test_speckle_filter_distance")
self.dist_msg_event_object = Event()
self.eucl_msg_event_object = Event()
self.publisher = self.create_publisher(LaserScan, "scan", 10)
qos = QoSProfile(depth=1, durability=QoSDurabilityPolicy.TRANSIENT_LOCAL)
self.publisher = self.create_publisher(LaserScan, "scan", qos_profile=qos)

def wait_for_subscribers(self, timeout):
timer_period = 0.1
Expand Down

0 comments on commit e02d296

Please sign in to comment.