Skip to content

Commit 4a5bbfa

Browse files
fix test_publisher_with_system_default_qos. (backport #2881) (#2882)
* fix test_publisher_with_system_default_qos. (#2881) Signed-off-by: Tomoya Fujita <[email protected]> (cherry picked from commit e6577c6) * intraprocess communication allowed only with volatile durability. Signed-off-by: Tomoya Fujita <[email protected]> --------- Signed-off-by: Tomoya Fujita <[email protected]> Co-authored-by: Tomoya Fujita <[email protected]>
1 parent 5237763 commit 4a5bbfa

File tree

1 file changed

+3
-1
lines changed

1 file changed

+3
-1
lines changed

rclcpp/test/rclcpp/test_publisher.cpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -184,10 +184,12 @@ TEST_F(TestPublisher, test_publisher_with_system_default_qos) {
184184
// explicitly enable intra-process comm with publisher option
185185
auto options = rclcpp::PublisherOptions();
186186
options.use_intra_process_comm = rclcpp::IntraProcessSetting::Enable;
187+
// intraprocess communication allowed only with volatile durability
188+
rclcpp::QoS qos = rclcpp::QoS(10).durability_volatile();
187189
using test_msgs::msg::Empty;
188190
ASSERT_NO_THROW(
189191
{
190-
auto publisher = node->create_publisher<Empty>("topic", rclcpp::SystemDefaultsQoS());
192+
auto publisher = node->create_publisher<Empty>("topic", qos, options);
191193
});
192194
}
193195

0 commit comments

Comments
 (0)