diff --git a/rclcpp/include/rclcpp/publisher.hpp b/rclcpp/include/rclcpp/publisher.hpp index 78b5700611..111d965183 100644 --- a/rclcpp/include/rclcpp/publisher.hpp +++ b/rclcpp/include/rclcpp/publisher.hpp @@ -178,7 +178,6 @@ class Publisher : public PublisherBase const rclcpp::PublisherOptionsWithAllocator & options) { // Topic is unused for now. - (void)topic; (void)options; // If needed, setup intra process communication. @@ -189,11 +188,13 @@ class Publisher : public PublisherBase // Register the publisher with the intra process manager. if (qos.history() != rclcpp::HistoryPolicy::KeepLast) { throw std::invalid_argument( - "intraprocess communication allowed only with keep last history qos policy"); + "intraprocess communication on topic '" + topic + + "' allowed only with keep last history qos policy"); } if (qos.depth() == 0) { throw std::invalid_argument( - "intraprocess communication is not allowed with a zero qos history depth value"); + "intraprocess communication on topic '" + topic + + "' is not allowed with a zero qos history depth value"); } if (qos.durability() != rclcpp::DurabilityPolicy::Volatile) { throw std::invalid_argument( diff --git a/rclcpp/include/rclcpp/subscription.hpp b/rclcpp/include/rclcpp/subscription.hpp index 11bf9c6e43..d00ec4d584 100644 --- a/rclcpp/include/rclcpp/subscription.hpp +++ b/rclcpp/include/rclcpp/subscription.hpp @@ -186,11 +186,13 @@ class Subscription : public SubscriptionBase auto qos_profile = get_actual_qos(); if (qos_profile.history() != rclcpp::HistoryPolicy::KeepLast) { throw std::invalid_argument( - "intraprocess communication allowed only with keep last history qos policy"); + "intraprocess communication on topic '" + topic_name + + "' allowed only with keep last history qos policy"); } if (qos_profile.depth() == 0) { throw std::invalid_argument( - "intraprocess communication is not allowed with 0 depth qos policy"); + "intraprocess communication on topic '" + topic_name + + "' is not allowed with 0 depth qos policy"); } if (qos_profile.durability() != rclcpp::DurabilityPolicy::Volatile) { throw std::invalid_argument( diff --git a/rclcpp/test/rclcpp/test_publisher.cpp b/rclcpp/test/rclcpp/test_publisher.cpp index 1679ca76f0..424615a1f2 100644 --- a/rclcpp/test/rclcpp/test_publisher.cpp +++ b/rclcpp/test/rclcpp/test_publisher.cpp @@ -422,7 +422,8 @@ TEST_F(TestPublisher, intra_process_publish_failures) { node->create_publisher( "topic", rclcpp::QoS(0), options), std::invalid_argument( - "intraprocess communication is not allowed with a zero qos history depth value")); + "intraprocess communication on topic 'topic' " + "is not allowed with a zero qos history depth value")); } TEST_F(TestPublisher, inter_process_publish_failures) {