latched_subscriber.h
Go to the documentation of this file.
1 #ifndef SWRI_ROSCPP_LATCHED_SUBSCRIBER_H_
2 #define SWRI_ROSCPP_LATCHED_SUBSCRIBER_H_
3 
4 
5 #include <ros/node_handle.h>
8 
9 namespace swri
10 {
11 // THIS CLASS IS DEPRECATED. This class has been replaced with a
12 // secondary interface to Subscriber that is initialized with the
13 // address of a boost::shared_ptr<M const> variable. When a message
14 // is received, it's value is assigned to this pointer. This approach
15 // provides the same simplicity as LatchedSubscriber without confusing
16 // semantics of faking a pointer type.
17 //
18 // This is an extension of the swri::Subscriber class to simplify the
19 // common case where you only care about the most recent value of a
20 // message rather than trying to queue up messages or responding to
21 // events. It has its own callback that is provided to
22 // swri::Subscriber and simply stores the message for the user to
23 // access whenever necessary.
24 template <class M>
26 {
27  private:
28  template <class M2>
30  {
33  msg_ = msg;
34  }
35  }; // struct LatchedReceiver
36 
38  M empty_;
39 
40  public:
42 
43  // Create a new latched subscriber. This is most like the
44  // swri::Subscriber interface, but you have to provide the template
45  // argument twice (once in your class declaration and at
46  // construction). See the initialize() method for a simpler
47  // alternative.
49  const std::string &topic,
50  const ros::TransportHints &transport_hints=ros::TransportHints());
51 
52  // Creates a latched subscriber in place. This is more convenient
53  // because you don't have to provide the template argument a second
54  // time.
55  void initialize(ros::NodeHandle &nh,
56  const std::string &topic,
57  const ros::TransportHints &transport_hints=ros::TransportHints());
58 
60 
61  // Return the value of the most recent message. This is guaranteed
62  // to be non-NULL if the messageCount() is non-zero, otherwise it
63  // may be null.
64  const boost::shared_ptr<M const>& data() const;
65  M const * operator->() const;
66 
67  void reset();
68 }; // class LatchedSubscriber
69 
70 template<class M>
72 {
73  // Setup an empty receiver so that we can assume receiver_ is
74  // non-null and avoid a lot of unnecessary NULL checks.
76 }
77 
78 template<class M>
80  ros::NodeHandle &nh,
81  const std::string &topic,
82  const ros::TransportHints &transport_hints)
83 {
84  ROS_WARN("swri_roscpp::LatchedSubscriber has been deprecated. See header for information.");
86  // It seems like there should be a better way to do this?
88  Subscriber(nh, topic, 1,
89  &LatchedReceiver<M>::handleMessage, receiver_.get(), transport_hints));
90 }
91 
92 template<class M>
94  ros::NodeHandle &nh,
95  const std::string &topic,
96  const ros::TransportHints &transport_hints)
97 {
98  *this = LatchedSubscriber<M>(nh, topic, transport_hints);
99 }
100 
101 
102 template<class M>
104 {
105  Subscriber::operator=(other);
106  receiver_ = other.receiver_;
107  return *this;
108 }
109 
110 template<class M>
112 {
113  return receiver_->msg_;
114 }
115 
116 template<class M>
118 {
119  if (receiver_->msg_) {
120  return receiver_->msg_.get();
121  } else {
122  return &empty_;
123  }
124 }
125 
126 template<class M>
128 {
129  receiver_->msg_.reset();
130  resetStatistics();
131 }
132 } // namespace swri
133 #endif // SWRI_ROSCPP_SUBSCRIBER_H_
134 
void resetStatistics()
Definition: subscriber.h:296
Subscriber & operator=(const Subscriber &other)
Definition: subscriber.h:252
LatchedSubscriber< M > & operator=(const LatchedSubscriber< M > &other)
#define ROS_WARN(...)
void initialize(ros::NodeHandle &nh, const std::string &topic, const ros::TransportHints &transport_hints=ros::TransportHints())
const boost::shared_ptr< M const > & data() const
boost::shared_ptr< M2 const > msg_
M const * operator->() const
boost::shared_ptr< LatchedReceiver< M > > receiver_
void handleMessage(const boost::shared_ptr< M2 const > &msg)


swri_roscpp
Author(s):
autogenerated on Tue Apr 6 2021 02:50:35