Skip to content

Commit 1a353f0

Browse files
Adding in topic name to logging on IPC issues (#2706) (#2709)
* Adding in topic name to logging on IPC issues Signed-off-by: Steve Macenski <[email protected]> * Update test matching output logging Signed-off-by: Steve Macenski <[email protected]> * adding in single quotes Signed-off-by: Steve Macenski <[email protected]> --------- Signed-off-by: Steve Macenski <[email protected]> (cherry picked from commit a13e16e) Co-authored-by: Steve Macenski <[email protected]>
1 parent e9edc3f commit 1a353f0

File tree

3 files changed

+10
-6
lines changed

3 files changed

+10
-6
lines changed

rclcpp/include/rclcpp/publisher.hpp

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -178,7 +178,6 @@ class Publisher : public PublisherBase
178178
const rclcpp::PublisherOptionsWithAllocator<AllocatorT> & options)
179179
{
180180
// Topic is unused for now.
181-
(void)topic;
182181
(void)options;
183182

184183
// If needed, setup intra process communication.
@@ -189,11 +188,13 @@ class Publisher : public PublisherBase
189188
// Register the publisher with the intra process manager.
190189
if (qos.history() != rclcpp::HistoryPolicy::KeepLast) {
191190
throw std::invalid_argument(
192-
"intraprocess communication allowed only with keep last history qos policy");
191+
"intraprocess communication on topic '" + topic +
192+
"' allowed only with keep last history qos policy");
193193
}
194194
if (qos.depth() == 0) {
195195
throw std::invalid_argument(
196-
"intraprocess communication is not allowed with a zero qos history depth value");
196+
"intraprocess communication on topic '" + topic +
197+
"' is not allowed with a zero qos history depth value");
197198
}
198199
if (qos.durability() != rclcpp::DurabilityPolicy::Volatile) {
199200
throw std::invalid_argument(

rclcpp/include/rclcpp/subscription.hpp

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -186,11 +186,13 @@ class Subscription : public SubscriptionBase
186186
auto qos_profile = get_actual_qos();
187187
if (qos_profile.history() != rclcpp::HistoryPolicy::KeepLast) {
188188
throw std::invalid_argument(
189-
"intraprocess communication allowed only with keep last history qos policy");
189+
"intraprocess communication on topic '" + topic_name +
190+
"' allowed only with keep last history qos policy");
190191
}
191192
if (qos_profile.depth() == 0) {
192193
throw std::invalid_argument(
193-
"intraprocess communication is not allowed with 0 depth qos policy");
194+
"intraprocess communication on topic '" + topic_name +
195+
"' is not allowed with 0 depth qos policy");
194196
}
195197
if (qos_profile.durability() != rclcpp::DurabilityPolicy::Volatile) {
196198
throw std::invalid_argument(

rclcpp/test/rclcpp/test_publisher.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -422,7 +422,8 @@ TEST_F(TestPublisher, intra_process_publish_failures) {
422422
node->create_publisher<test_msgs::msg::Empty>(
423423
"topic", rclcpp::QoS(0), options),
424424
std::invalid_argument(
425-
"intraprocess communication is not allowed with a zero qos history depth value"));
425+
"intraprocess communication on topic 'topic' "
426+
"is not allowed with a zero qos history depth value"));
426427
}
427428

428429
TEST_F(TestPublisher, inter_process_publish_failures) {

0 commit comments

Comments
 (0)