We read every piece of feedback, and take your input very seriously.
To see all available qualifiers, see our documentation.
There was an error while loading. Please reload this page.
2 parents b0ff053 + e4e56ef commit d760ba3Copy full SHA for d760ba3
rclcpp/include/rclcpp/experimental/subscription_intra_process_base.hpp
@@ -142,8 +142,12 @@ class SubscriptionIntraProcessBase : public rclcpp::Waitable
142
on_new_message_callback_ = new_callback;
143
144
if (unread_count_ > 0) {
145
- // Use qos profile depth as upper bound for unread_count_
146
- on_new_message_callback_(std::min(unread_count_, qos_profile_.depth));
+ if (qos_profile_.history == RMW_QOS_POLICY_HISTORY_KEEP_ALL || qos_profile_.depth == 0) {
+ on_new_message_callback_(unread_count_);
147
+ } else {
148
+ // Use qos profile depth as upper bound for unread_count_
149
+ on_new_message_callback_(std::min(unread_count_, qos_profile_.depth));
150
+ }
151
unread_count_ = 0;
152
}
153
0 commit comments