Skip to content

Commit e02d296

Browse files
committed
Durability policy for publisher in speckle filter test
1 parent 4440285 commit e02d296

File tree

1 file changed

+3
-1
lines changed

1 file changed

+3
-1
lines changed

test/test_speckle_filter.test.py

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@
1818
import pytest
1919
import rclpy
2020
from rclpy.node import Node
21+
from rclpy.qos import QoSProfile, QoSDurabilityPolicy
2122
from sensor_msgs.msg import LaserScan
2223

2324

@@ -91,7 +92,8 @@ def __init__(self):
9192
super().__init__("test_speckle_filter_distance")
9293
self.dist_msg_event_object = Event()
9394
self.eucl_msg_event_object = Event()
94-
self.publisher = self.create_publisher(LaserScan, "scan", 10)
95+
qos = QoSProfile(depth=1, durability=QoSDurabilityPolicy.TRANSIENT_LOCAL)
96+
self.publisher = self.create_publisher(LaserScan, "scan", qos_profile=qos)
9597

9698
def wait_for_subscribers(self, timeout):
9799
timer_period = 0.1

0 commit comments

Comments
 (0)