Skip to content

Commit 016cfea

Browse files
authored
apply actual QoS from rmw to the IPC publisher. (#2707)
* apply actual QoS from rmw to the IPC publisher. Signed-off-by: Tomoya Fujita <Tomoya.Fujita@sony.com> * address uncrustify warning. Signed-off-by: Tomoya Fujita <Tomoya.Fujita@sony.com> --------- Signed-off-by: Tomoya Fujita <Tomoya.Fujita@sony.com>
1 parent a13e16e commit 016cfea

3 files changed

Lines changed: 43 additions & 12 deletions

File tree

rclcpp/include/rclcpp/publisher.hpp

Lines changed: 8 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -146,32 +146,34 @@ class Publisher : public PublisherBase
146146
const rclcpp::QoS & qos,
147147
const rclcpp::PublisherOptionsWithAllocator<AllocatorT> & options)
148148
{
149-
// Topic is unused for now.
149+
(void)qos;
150150
(void)options;
151151

152152
// If needed, setup intra process communication.
153153
if (rclcpp::detail::resolve_use_intra_process(options_, *node_base)) {
154154
auto context = node_base->get_context();
155155
// Get the intra process manager instance for this context.
156156
auto ipm = context->get_sub_context<rclcpp::experimental::IntraProcessManager>();
157-
// Register the publisher with the intra process manager.
158-
if (qos.history() != rclcpp::HistoryPolicy::KeepLast) {
157+
// Check if the QoS is compatible with intra-process.
158+
auto qos_profile = get_actual_qos();
159+
if (qos_profile.history() != rclcpp::HistoryPolicy::KeepLast) {
159160
throw std::invalid_argument(
160161
"intraprocess communication on topic '" + topic +
161162
"' allowed only with keep last history qos policy");
162163
}
163-
if (qos.depth() == 0) {
164+
if (qos_profile.depth() == 0) {
164165
throw std::invalid_argument(
165166
"intraprocess communication on topic '" + topic +
166167
"' is not allowed with a zero qos history depth value");
167168
}
168-
if (qos.durability() == rclcpp::DurabilityPolicy::TransientLocal) {
169+
if (qos_profile.durability() == rclcpp::DurabilityPolicy::TransientLocal) {
169170
buffer_ = rclcpp::experimental::create_intra_process_buffer<
170171
ROSMessageType, ROSMessageTypeAllocator, ROSMessageTypeDeleter>(
171172
rclcpp::detail::resolve_intra_process_buffer_type(options_.intra_process_buffer_type),
172-
qos,
173+
qos_profile,
173174
std::make_shared<ROSMessageTypeAllocator>(ros_message_type_allocator_));
174175
}
176+
// Register the publisher with the intra process manager.
175177
uint64_t intra_process_publisher_id = ipm->add_publisher(this->shared_from_this(), buffer_);
176178
this->setup_intra_process(
177179
intra_process_publisher_id,

rclcpp/test/rclcpp/test_create_subscription.cpp

Lines changed: 16 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -92,3 +92,19 @@ TEST_F(TestCreateSubscription, create_with_statistics) {
9292
ASSERT_NE(nullptr, subscription);
9393
EXPECT_STREQ("/ns/topic_name", subscription->get_topic_name());
9494
}
95+
96+
TEST_F(TestCreateSubscription, create_with_intra_process_com) {
97+
auto node = std::make_shared<rclcpp::Node>("my_node", "/ns");
98+
auto options = rclcpp::SubscriptionOptions();
99+
options.use_intra_process_comm = rclcpp::IntraProcessSetting::Enable;
100+
101+
auto callback = [](test_msgs::msg::Empty::ConstSharedPtr) {};
102+
rclcpp::Subscription<test_msgs::msg::Empty>::SharedPtr subscription;
103+
ASSERT_NO_THROW(
104+
{
105+
subscription = rclcpp::create_subscription<test_msgs::msg::Empty>(
106+
node, "topic_name", rclcpp::SystemDefaultsQoS(), callback, options);
107+
});
108+
ASSERT_NE(nullptr, subscription);
109+
EXPECT_STREQ("/ns/topic_name", subscription->get_topic_name());
110+
}

rclcpp/test/rclcpp/test_publisher.cpp

Lines changed: 19 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -187,6 +187,21 @@ TEST_F(TestPublisher, various_creation_signatures) {
187187
}
188188
}
189189

190+
/*
191+
Testing publisher with intraprocess enabled and SystemDefaultQoS
192+
*/
193+
TEST_F(TestPublisher, test_publisher_with_system_default_qos) {
194+
initialize(rclcpp::NodeOptions().use_intra_process_comms(false));
195+
// explicitly enable intra-process comm with publisher option
196+
auto options = rclcpp::PublisherOptions();
197+
options.use_intra_process_comm = rclcpp::IntraProcessSetting::Enable;
198+
using test_msgs::msg::Empty;
199+
ASSERT_NO_THROW(
200+
{
201+
auto publisher = node->create_publisher<Empty>("topic", rclcpp::SystemDefaultsQoS());
202+
});
203+
}
204+
190205
/*
191206
Testing publisher with intraprocess enabled and invalid QoS
192207
*/
@@ -432,12 +447,10 @@ TEST_F(TestPublisher, intra_process_publish_failures) {
432447
publisher->get_publisher_handle().get(), msg.get()));
433448
}
434449
}
435-
RCLCPP_EXPECT_THROW_EQ(
436-
node->create_publisher<test_msgs::msg::Empty>(
437-
"topic", rclcpp::QoS(0), options),
438-
std::invalid_argument(
439-
"intraprocess communication on topic 'topic' "
440-
"is not allowed with a zero qos history depth value"));
450+
// a zero depth with KEEP_LAST doesn't make sense,
451+
// this will be interpreted as SystemDefaultQoS by rclcpp.
452+
EXPECT_NO_THROW(
453+
node->create_publisher<test_msgs::msg::Empty>("topic", rclcpp::QoS(0), options));
441454
}
442455

443456
TEST_F(TestPublisher, inter_process_publish_failures) {

0 commit comments

Comments
 (0)