-
Notifications
You must be signed in to change notification settings - Fork 85
Expose subscription options #53
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Changes from all commits
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
| Original file line number | Diff line number | Diff line change |
|---|---|---|
|
|
@@ -43,6 +43,7 @@ | |
| namespace message_filters | ||
| { | ||
|
|
||
| template <typename AllocatorT=std::allocator<void>> | ||
| class SubscriberBase | ||
| { | ||
| public: | ||
|
|
@@ -56,7 +57,12 @@ class SubscriberBase | |
| * \param topic The topic to subscribe to. | ||
| * \param qos (optional) The rmw qos profile to use to subscribe | ||
| */ | ||
| virtual void subscribe(rclcpp::Node::SharedPtr node, const std::string& topic, const rmw_qos_profile_t qos = rmw_qos_profile_default) = 0; | ||
| virtual void subscribe( | ||
| rclcpp::Node::SharedPtr node, | ||
| const std::string& topic, | ||
| const rmw_qos_profile_t qos = rmw_qos_profile_default, | ||
| rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> options = | ||
| rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>()) = 0; | ||
|
Comment on lines
+64
to
+65
Member
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. It would be nice if we could introduce these options without breaking API, but I'm not sure if that's possible in a pure virtual class. To be honest, it's not clear to me why we have this abstract class to begin with, it doesn't appear to be used anywhere (besides being implemented by Pinging @mjcarroll for thoughts (I think you're the maintainer?).
Member
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. The way to avoid breaking API is to keep the old virtual void subscribe(
rclcpp::Node::SharedPtr node,
const std::string& topic,
const rmw_qos_profile_t qos = rmw_qos_profile_default) = 0;and add a new virtual void subscribe(
rclcpp::Node::SharedPtr node,
const std::string& topic,
const rmw_qos_profile_t qos,
rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> options)
{
(void)options;
// --> warn about method not overriden here <--
this->subscribe(node, topic, qos);
};
Member
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
It doesn't seem to be meant to be extended by external users, so it might be ok to just add new virtual methods to it.
Member
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. If it's not meant to be extended, then I think we could just add the new method to the concrete class. We could go so far as to deprecate the pure virtual class and/or remove it in a separate PR, to avoid similar API/ABI issues in the future.
Member
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I'm also okay with your proposal to implement and warn about the non-overridden method #53 (comment) |
||
|
|
||
| /** | ||
| * \brief Subscribe to a topic. | ||
|
|
@@ -67,7 +73,12 @@ class SubscriberBase | |
| * \param topic The topic to subscribe to. | ||
| * \param qos (optional) The rmw qos profile to use to subscribe | ||
| */ | ||
| virtual void subscribe(rclcpp::Node * node, const std::string& topic, const rmw_qos_profile_t qos = rmw_qos_profile_default) = 0; | ||
| virtual void subscribe( | ||
| rclcpp::Node * node, | ||
| const std::string& topic, | ||
| const rmw_qos_profile_t qos = rmw_qos_profile_default, | ||
| rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> options = | ||
| rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>()) = 0; | ||
| /** | ||
| * \brief Re-subscribe to a topic. Only works if this subscriber has previously been subscribed to a topic. | ||
| */ | ||
|
|
@@ -77,7 +88,8 @@ class SubscriberBase | |
| */ | ||
| virtual void unsubscribe() = 0; | ||
| }; | ||
| typedef std::shared_ptr<SubscriberBase> SubscriberBasePtr; | ||
| template <typename AllocatorT=std::allocator<void>> | ||
| using SubscriberBasePtr = std::shared_ptr<SubscriberBase<AllocatorT>>; | ||
|
|
||
| /** | ||
| * \brief ROS subscription filter. | ||
|
|
@@ -98,8 +110,11 @@ typedef std::shared_ptr<SubscriberBase> SubscriberBasePtr; | |
| void callback(const std::shared_ptr<M const>&); | ||
| \endverbatim | ||
| */ | ||
| template<class M> | ||
| class Subscriber : public SubscriberBase, public SimpleFilter<M> | ||
| template< | ||
| class M, | ||
| typename AllocatorT=std::allocator<void> | ||
| > | ||
| class Subscriber : public SubscriberBase<AllocatorT>, public SimpleFilter<M> | ||
| { | ||
| public: | ||
| typedef MessageEvent<M const> EventType; | ||
|
|
@@ -113,14 +128,24 @@ class Subscriber : public SubscriberBase, public SimpleFilter<M> | |
| * \param topic The topic to subscribe to. | ||
| * \param qos (optional) The rmw qos profile to use to subscribe | ||
| */ | ||
| Subscriber(rclcpp::Node::SharedPtr node, const std::string& topic, const rmw_qos_profile_t qos = rmw_qos_profile_default) | ||
| Subscriber( | ||
| rclcpp::Node::SharedPtr node, | ||
| const std::string& topic, | ||
| const rmw_qos_profile_t qos = rmw_qos_profile_default, | ||
| rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> options = | ||
| rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>()) | ||
| { | ||
| subscribe(node, topic, qos); | ||
| subscribe(node, topic, qos, options); | ||
| } | ||
|
|
||
| Subscriber(rclcpp::Node* node, const std::string& topic, const rmw_qos_profile_t qos = rmw_qos_profile_default) | ||
| Subscriber( | ||
| rclcpp::Node* node, | ||
| const std::string& topic, | ||
| const rmw_qos_profile_t qos = rmw_qos_profile_default, | ||
| rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> options = | ||
| rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>()) | ||
| { | ||
| subscribe(node, topic, qos); | ||
| subscribe(node, topic, qos, options); | ||
| } | ||
|
|
||
| /** | ||
|
|
@@ -142,9 +167,14 @@ class Subscriber : public SubscriberBase, public SimpleFilter<M> | |
| * \param topic The topic to subscribe to. | ||
| * \param qos (optional) The rmw qos profile to use to subscribe | ||
| */ | ||
| void subscribe(rclcpp::Node::SharedPtr node, const std::string& topic, const rmw_qos_profile_t qos = rmw_qos_profile_default) | ||
| void subscribe( | ||
| rclcpp::Node::SharedPtr node, | ||
| const std::string& topic, | ||
| const rmw_qos_profile_t qos = rmw_qos_profile_default, | ||
| rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> options = | ||
| rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>()) | ||
| { | ||
| subscribe(node.get(), topic, qos); | ||
| subscribe(node.get(), topic, qos, options); | ||
| node_raw_ = nullptr; | ||
| node_shared_ = node; | ||
| } | ||
|
|
@@ -159,7 +189,12 @@ class Subscriber : public SubscriberBase, public SimpleFilter<M> | |
| * \param qos (optional) The rmw qos profile to use to subscribe | ||
| */ | ||
| // TODO(wjwwood): deprecate in favor of API's that use `rclcpp::QoS` instead. | ||
| void subscribe(rclcpp::Node * node, const std::string& topic, const rmw_qos_profile_t qos = rmw_qos_profile_default) | ||
| void subscribe( | ||
| rclcpp::Node * node, | ||
| const std::string& topic, | ||
| const rmw_qos_profile_t qos = rmw_qos_profile_default, | ||
| rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> options = | ||
| rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>()) | ||
| { | ||
| unsubscribe(); | ||
|
|
||
|
|
@@ -169,10 +204,11 @@ class Subscriber : public SubscriberBase, public SimpleFilter<M> | |
| rclcpp::QoS rclcpp_qos(rclcpp::QoSInitialization::from_rmw(qos)); | ||
| rclcpp_qos.get_rmw_qos_profile() = qos; | ||
| qos_ = qos; | ||
| options_ = options; | ||
| sub_ = node->create_subscription<M>(topic, rclcpp_qos, | ||
| [this](std::shared_ptr<M const> msg) { | ||
| this->cb(EventType(msg)); | ||
| }); | ||
| }, options); | ||
|
|
||
| node_raw_ = node; | ||
| } | ||
|
|
@@ -186,9 +222,9 @@ class Subscriber : public SubscriberBase, public SimpleFilter<M> | |
| if (!topic_.empty()) | ||
| { | ||
| if (node_raw_ != nullptr) { | ||
| subscribe(node_raw_, topic_, qos_); | ||
| subscribe(node_raw_, topic_, qos_, options_); | ||
| } else if (node_shared_ != nullptr) { | ||
| subscribe(node_shared_, topic_, qos_); | ||
| subscribe(node_shared_, topic_, qos_, options_); | ||
| } | ||
| } | ||
| } | ||
|
|
@@ -242,6 +278,7 @@ class Subscriber : public SubscriberBase, public SimpleFilter<M> | |
|
|
||
| std::string topic_; | ||
| rmw_qos_profile_t qos_; | ||
| rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> options_; | ||
| }; | ||
|
|
||
| } // namespace message_filters | ||
|
|
||
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
I don't think that making this virtual class templated makes much sense, I would just use
rclcpp::SubscriptionOptionsbelow