Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #ifndef ROSCPP_SUBSCRIBER_HANDLE_H
00029 #define ROSCPP_SUBSCRIBER_HANDLE_H
00030
00031 #include "common.h"
00032 #include "ros/forwards.h"
00033 #include "ros/subscription_callback_helper.h"
00034
00035 namespace ros
00036 {
00037
00046 class ROSCPP_DECL Subscriber
00047 {
00048 public:
00049 Subscriber() {}
00050 Subscriber(const Subscriber& rhs);
00051 ~Subscriber();
00052
00062 void shutdown();
00063
00064 std::string getTopic() const;
00065
00069 uint32_t getNumPublishers() const;
00070
00071 operator void*() const { return (impl_ && impl_->isValid()) ? (void*)1 : (void*)0; }
00072
00073 bool operator<(const Subscriber& rhs) const
00074 {
00075 return impl_ < rhs.impl_;
00076 }
00077
00078 bool operator==(const Subscriber& rhs) const
00079 {
00080 return impl_ == rhs.impl_;
00081 }
00082
00083 bool operator!=(const Subscriber& rhs) const
00084 {
00085 return impl_ != rhs.impl_;
00086 }
00087
00088 private:
00089
00090 Subscriber(const std::string& topic, const NodeHandle& node_handle,
00091 const SubscriptionCallbackHelperPtr& helper);
00092
00093 class Impl
00094 {
00095 public:
00096 Impl();
00097 ~Impl();
00098
00099 void unsubscribe();
00100 bool isValid() const;
00101
00102 std::string topic_;
00103 NodeHandlePtr node_handle_;
00104 SubscriptionCallbackHelperPtr helper_;
00105 bool unsubscribed_;
00106 };
00107 typedef boost::shared_ptr<Impl> ImplPtr;
00108 typedef boost::weak_ptr<Impl> ImplWPtr;
00109
00110 ImplPtr impl_;
00111
00112 friend class NodeHandle;
00113 friend class NodeHandleBackingCollection;
00114 };
00115 typedef std::vector<Subscriber> V_Subscriber;
00116
00117 }
00118
00119 #endif // ROSCPP_PUBLISHER_HANDLE_H
00120
00121
roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim
autogenerated on Mon Oct 6 2014 11:46:44