Skip to content

Commit 838ee83

Browse files
committed
Revert "Revert "Qos configurability (#1408)" (#1459)"
This reverts commit 27d1b11. Signed-off-by: Ivan Santiago Paunovic <[email protected]>
1 parent 27d1b11 commit 838ee83

16 files changed

+1057
-55
lines changed

rclcpp/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -85,6 +85,7 @@ set(${PROJECT_NAME}_SRCS
8585
src/rclcpp/publisher_base.cpp
8686
src/rclcpp/qos.cpp
8787
src/rclcpp/qos_event.cpp
88+
src/rclcpp/qos_overriding_options.cpp
8889
src/rclcpp/serialization.cpp
8990
src/rclcpp/serialized_message.cpp
9091
src/rclcpp/service.cpp

rclcpp/include/rclcpp/create_publisher.hpp

Lines changed: 66 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -17,54 +17,108 @@
1717

1818
#include <memory>
1919
#include <string>
20+
#include <utility>
2021

2122
#include "rclcpp/node_interfaces/get_node_topics_interface.hpp"
2223
#include "rclcpp/node_interfaces/node_topics_interface.hpp"
2324
#include "rclcpp/node_options.hpp"
2425
#include "rclcpp/publisher_factory.hpp"
2526
#include "rclcpp/publisher_options.hpp"
2627
#include "rclcpp/qos.hpp"
28+
#include "rclcpp/qos_overriding_options.hpp"
29+
#include "rclcpp/detail/qos_parameters.hpp"
30+
2731
#include "rmw/qos_profiles.h"
2832

2933
namespace rclcpp
3034
{
3135

36+
namespace detail
37+
{
3238
/// Create and return a publisher of the given MessageT type.
33-
/**
34-
* The NodeT type only needs to have a method called get_node_topics_interface()
35-
* which returns a shared_ptr to a NodeTopicsInterface.
36-
*/
3739
template<
3840
typename MessageT,
3941
typename AllocatorT = std::allocator<void>,
4042
typename PublisherT = rclcpp::Publisher<MessageT, AllocatorT>,
41-
typename NodeT>
43+
typename NodeParametersT,
44+
typename NodeTopicsT>
4245
std::shared_ptr<PublisherT>
4346
create_publisher(
44-
NodeT & node,
47+
NodeParametersT & node_parameters,
48+
NodeTopicsT & node_topics,
4549
const std::string & topic_name,
4650
const rclcpp::QoS & qos,
4751
const rclcpp::PublisherOptionsWithAllocator<AllocatorT> & options = (
4852
rclcpp::PublisherOptionsWithAllocator<AllocatorT>()
4953
)
5054
)
5155
{
52-
// Extract the NodeTopicsInterface from the NodeT.
53-
using rclcpp::node_interfaces::get_node_topics_interface;
54-
auto node_topics = get_node_topics_interface(node);
56+
auto node_topics_interface = rclcpp::node_interfaces::get_node_topics_interface(node_topics);
57+
const rclcpp::QoS & actual_qos = options.qos_overriding_options.policy_kinds.size() ?
58+
rclcpp::detail::declare_qos_parameters(
59+
options.qos_overriding_options, node_parameters,
60+
node_topics_interface->resolve_topic_name(topic_name),
61+
qos, rclcpp::detail::PublisherQosParametersTraits{}) :
62+
qos;
5563

5664
// Create the publisher.
57-
auto pub = node_topics->create_publisher(
65+
auto pub = node_topics_interface->create_publisher(
5866
topic_name,
5967
rclcpp::create_publisher_factory<MessageT, AllocatorT, PublisherT>(options),
60-
qos
68+
actual_qos
6169
);
6270

6371
// Add the publisher to the node topics interface.
64-
node_topics->add_publisher(pub, options.callback_group);
72+
node_topics_interface->add_publisher(pub, options.callback_group);
6573

6674
return std::dynamic_pointer_cast<PublisherT>(pub);
6775
}
76+
} // namespace detail
77+
78+
79+
/// Create and return a publisher of the given MessageT type.
80+
/**
81+
* The NodeT type only needs to have a method called get_node_topics_interface()
82+
* which returns a shared_ptr to a NodeTopicsInterface.
83+
*/
84+
template<
85+
typename MessageT,
86+
typename AllocatorT = std::allocator<void>,
87+
typename PublisherT = rclcpp::Publisher<MessageT, AllocatorT>,
88+
typename NodeT>
89+
std::shared_ptr<PublisherT>
90+
create_publisher(
91+
NodeT & node,
92+
const std::string & topic_name,
93+
const rclcpp::QoS & qos,
94+
const rclcpp::PublisherOptionsWithAllocator<AllocatorT> & options = (
95+
rclcpp::PublisherOptionsWithAllocator<AllocatorT>()
96+
)
97+
)
98+
{
99+
return detail::create_publisher<MessageT, AllocatorT, PublisherT>(
100+
node, node, topic_name, qos, options);
101+
}
102+
103+
/// Create and return a publisher of the given MessageT type.
104+
template<
105+
typename MessageT,
106+
typename AllocatorT = std::allocator<void>,
107+
typename PublisherT = rclcpp::Publisher<MessageT, AllocatorT>>
108+
std::shared_ptr<PublisherT>
109+
create_publisher(
110+
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr & node_parameters,
111+
rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr & node_topics,
112+
const std::string & topic_name,
113+
const rclcpp::QoS & qos,
114+
const rclcpp::PublisherOptionsWithAllocator<AllocatorT> & options = (
115+
rclcpp::PublisherOptionsWithAllocator<AllocatorT>()
116+
)
117+
)
118+
{
119+
return detail::create_publisher<MessageT, AllocatorT, PublisherT>(
120+
node_parameters, node_topics, topic_name, qos, options);
121+
}
68122

69123
} // namespace rclcpp
70124

rclcpp/include/rclcpp/create_subscription.hpp

Lines changed: 119 additions & 43 deletions
Original file line numberDiff line numberDiff line change
@@ -41,44 +41,21 @@
4141
namespace rclcpp
4242
{
4343

44-
/// Create and return a subscription of the given MessageT type.
45-
/**
46-
* The NodeT type only needs to have a method called get_node_topics_interface()
47-
* which returns a shared_ptr to a NodeTopicsInterface, or be a
48-
* NodeTopicsInterface pointer itself.
49-
*
50-
* \tparam MessageT
51-
* \tparam CallbackT
52-
* \tparam AllocatorT
53-
* \tparam CallbackMessageT
54-
* \tparam SubscriptionT
55-
* \tparam MessageMemoryStrategyT
56-
* \tparam NodeT
57-
* \param node
58-
* \param topic_name
59-
* \param qos
60-
* \param callback
61-
* \param options
62-
* \param msg_mem_strat
63-
* \return the created subscription
64-
* \throws std::invalid_argument if topic statistics is enabled and the publish period is
65-
* less than or equal to zero.
66-
*/
44+
namespace detail
45+
{
6746
template<
6847
typename MessageT,
6948
typename CallbackT,
70-
typename AllocatorT = std::allocator<void>,
71-
typename CallbackMessageT =
72-
typename rclcpp::subscription_traits::has_message_type<CallbackT>::type,
73-
typename SubscriptionT = rclcpp::Subscription<CallbackMessageT, AllocatorT>,
74-
typename MessageMemoryStrategyT = rclcpp::message_memory_strategy::MessageMemoryStrategy<
75-
CallbackMessageT,
76-
AllocatorT
77-
>,
78-
typename NodeT>
49+
typename AllocatorT,
50+
typename CallbackMessageT,
51+
typename SubscriptionT,
52+
typename MessageMemoryStrategyT,
53+
typename NodeParametersT,
54+
typename NodeTopicsT>
7955
typename std::shared_ptr<SubscriptionT>
8056
create_subscription(
81-
NodeT && node,
57+
NodeParametersT & node_parameters,
58+
NodeTopicsT & node_topics,
8259
const std::string & topic_name,
8360
const rclcpp::QoS & qos,
8461
CallbackT && callback,
@@ -91,14 +68,14 @@ create_subscription(
9168
)
9269
{
9370
using rclcpp::node_interfaces::get_node_topics_interface;
94-
auto node_topics = get_node_topics_interface(std::forward<NodeT>(node));
71+
auto node_topics_interface = get_node_topics_interface(node_topics);
9572

9673
std::shared_ptr<rclcpp::topic_statistics::SubscriptionTopicStatistics<CallbackMessageT>>
9774
subscription_topic_stats = nullptr;
9875

9976
if (rclcpp::detail::resolve_enable_topic_statistics(
10077
options,
101-
*node_topics->get_node_base_interface()))
78+
*node_topics_interface->get_node_base_interface()))
10279
{
10380
if (options.topic_stats_options.publish_period <= std::chrono::milliseconds(0)) {
10481
throw std::invalid_argument(
@@ -107,15 +84,16 @@ create_subscription(
10784
" ms");
10885
}
10986

110-
std::shared_ptr<Publisher<statistics_msgs::msg::MetricsMessage>> publisher =
111-
create_publisher<statistics_msgs::msg::MetricsMessage>(
112-
node,
87+
std::shared_ptr<Publisher<statistics_msgs::msg::MetricsMessage>>
88+
publisher = rclcpp::detail::create_publisher<statistics_msgs::msg::MetricsMessage>(
89+
node_parameters,
90+
node_topics_interface,
11391
options.topic_stats_options.publish_topic,
11492
qos);
11593

11694
subscription_topic_stats = std::make_shared<
11795
rclcpp::topic_statistics::SubscriptionTopicStatistics<CallbackMessageT>
118-
>(node_topics->get_node_base_interface()->get_name(), publisher);
96+
>(node_topics_interface->get_node_base_interface()->get_name(), publisher);
11997

12098
std::weak_ptr<
12199
rclcpp::topic_statistics::SubscriptionTopicStatistics<CallbackMessageT>
@@ -127,14 +105,14 @@ create_subscription(
127105
}
128106
};
129107

130-
auto node_timer_interface = node_topics->get_node_timers_interface();
108+
auto node_timer_interface = node_topics_interface->get_node_timers_interface();
131109

132110
auto timer = create_wall_timer(
133111
std::chrono::duration_cast<std::chrono::nanoseconds>(
134112
options.topic_stats_options.publish_period),
135113
sub_call_back,
136114
options.callback_group,
137-
node_topics->get_node_base_interface(),
115+
node_topics_interface->get_node_base_interface(),
138116
node_timer_interface
139117
);
140118

@@ -148,11 +126,109 @@ create_subscription(
148126
subscription_topic_stats
149127
);
150128

151-
auto sub = node_topics->create_subscription(topic_name, factory, qos);
152-
node_topics->add_subscription(sub, options.callback_group);
129+
const rclcpp::QoS & actual_qos = options.qos_overriding_options.policy_kinds.size() ?
130+
rclcpp::detail::declare_qos_parameters(
131+
options.qos_overriding_options, node_parameters,
132+
node_topics_interface->resolve_topic_name(topic_name),
133+
qos, rclcpp::detail::SubscriptionQosParametersTraits{}) :
134+
qos;
135+
136+
auto sub = node_topics_interface->create_subscription(topic_name, factory, actual_qos);
137+
node_topics_interface->add_subscription(sub, options.callback_group);
153138

154139
return std::dynamic_pointer_cast<SubscriptionT>(sub);
155140
}
141+
} // namespace detail
142+
143+
/// Create and return a subscription of the given MessageT type.
144+
/**
145+
* The NodeT type only needs to have a method called get_node_topics_interface()
146+
* which returns a shared_ptr to a NodeTopicsInterface, or be a
147+
* NodeTopicsInterface pointer itself.
148+
*
149+
* \tparam MessageT
150+
* \tparam CallbackT
151+
* \tparam AllocatorT
152+
* \tparam CallbackMessageT
153+
* \tparam SubscriptionT
154+
* \tparam MessageMemoryStrategyT
155+
* \tparam NodeT
156+
* \param node
157+
* \param topic_name
158+
* \param qos
159+
* \param callback
160+
* \param options
161+
* \param msg_mem_strat
162+
* \return the created subscription
163+
* \throws std::invalid_argument if topic statistics is enabled and the publish period is
164+
* less than or equal to zero.
165+
*/
166+
template<
167+
typename MessageT,
168+
typename CallbackT,
169+
typename AllocatorT = std::allocator<void>,
170+
typename CallbackMessageT =
171+
typename rclcpp::subscription_traits::has_message_type<CallbackT>::type,
172+
typename SubscriptionT = rclcpp::Subscription<CallbackMessageT, AllocatorT>,
173+
typename MessageMemoryStrategyT = rclcpp::message_memory_strategy::MessageMemoryStrategy<
174+
CallbackMessageT,
175+
AllocatorT
176+
>,
177+
typename NodeT>
178+
typename std::shared_ptr<SubscriptionT>
179+
create_subscription(
180+
NodeT & node,
181+
const std::string & topic_name,
182+
const rclcpp::QoS & qos,
183+
CallbackT && callback,
184+
const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> & options = (
185+
rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>()
186+
),
187+
typename MessageMemoryStrategyT::SharedPtr msg_mem_strat = (
188+
MessageMemoryStrategyT::create_default()
189+
)
190+
)
191+
{
192+
return rclcpp::detail::create_subscription<
193+
MessageT, CallbackT, AllocatorT, CallbackMessageT, SubscriptionT, MessageMemoryStrategyT>(
194+
node, node, topic_name, qos, std::forward<CallbackT>(callback), options, msg_mem_strat);
195+
}
196+
197+
/// Create and return a subscription of the given MessageT type.
198+
/**
199+
* See \ref create_subscription().
200+
*/
201+
template<
202+
typename MessageT,
203+
typename CallbackT,
204+
typename AllocatorT = std::allocator<void>,
205+
typename CallbackMessageT =
206+
typename rclcpp::subscription_traits::has_message_type<CallbackT>::type,
207+
typename SubscriptionT = rclcpp::Subscription<CallbackMessageT, AllocatorT>,
208+
typename MessageMemoryStrategyT = rclcpp::message_memory_strategy::MessageMemoryStrategy<
209+
CallbackMessageT,
210+
AllocatorT
211+
>>
212+
typename std::shared_ptr<SubscriptionT>
213+
create_subscription(
214+
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr & node_parameters,
215+
rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr & node_topics,
216+
const std::string & topic_name,
217+
const rclcpp::QoS & qos,
218+
CallbackT && callback,
219+
const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> & options = (
220+
rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>()
221+
),
222+
typename MessageMemoryStrategyT::SharedPtr msg_mem_strat = (
223+
MessageMemoryStrategyT::create_default()
224+
)
225+
)
226+
{
227+
return rclcpp::detail::create_subscription<
228+
MessageT, CallbackT, AllocatorT, CallbackMessageT, SubscriptionT, MessageMemoryStrategyT>(
229+
node_parameters, node_topics, topic_name, qos,
230+
std::forward<CallbackT>(callback), options, msg_mem_strat);
231+
}
156232

157233
} // namespace rclcpp
158234

0 commit comments

Comments
 (0)