Skip to content

Commit

Permalink
feat(tier4_autoware_utils): default QoS setting of polling subscriber
Browse files Browse the repository at this point in the history
Signed-off-by: Mamoru Sobue <[email protected]>
  • Loading branch information
soblin committed May 13, 2024
1 parent fd89ca2 commit 775db2f
Showing 1 changed file with 15 additions and 3 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -30,24 +30,36 @@ class InterProcessPollingSubscriber
std::optional<T> data_;

public:
explicit InterProcessPollingSubscriber(rclcpp::Node * node, const std::string & topic_name)
explicit InterProcessPollingSubscriber(
rclcpp::Node * node, const std::string & topic_name, const rclcpp::QoS & qos = rclcpp::QoS{1})
{
auto noexec_callback_group =
node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive, false);
auto noexec_subscription_options = rclcpp::SubscriptionOptions();
noexec_subscription_options.callback_group = noexec_callback_group;

subscriber_ = node->create_subscription<T>(
topic_name, rclcpp::QoS{1},
topic_name, qos,
[node]([[maybe_unused]] const typename T::ConstSharedPtr msg) { assert(false); },
noexec_subscription_options);
if (qos.get_rmw_qos_profile().depth > 1) {
RCLCPP_WARN(
node->get_logger(),
"InterProcessPollingSubscriber will be used with depth > 1, which may cause inefficient "
"serialization while updateLatestData()");
}
};
bool updateLatestData()
{
rclcpp::MessageInfo message_info;
T tmp;
// The queue size (QoS) must be 1 to get the last message data.
if (subscriber_->take(tmp, message_info)) {
bool is_latest_message_consumed = false;
// pop the queue until latest data
while (subscriber_->take(tmp, message_info)) {
is_latest_message_consumed = true;
}
if (is_latest_message_consumed) {
data_ = tmp;
}
return data_.has_value();
Expand Down

0 comments on commit 775db2f

Please sign in to comment.