Go to the documentation of this file.00001 #ifndef SWRI_ROSCPP_LATCHED_SUBSCRIBER_H_
00002 #define SWRI_ROSCPP_LATCHED_SUBSCRIBER_H_
00003
00004
00005 #include <ros/node_handle.h>
00006 #include <diagnostic_updater/DiagnosticStatusWrapper.h>
00007 #include <swri_roscpp/subscriber.h>
00008
00009 namespace swri
00010 {
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024 template <class M>
00025 class LatchedSubscriber : public Subscriber
00026 {
00027 private:
00028 template <class M2>
00029 struct LatchedReceiver
00030 {
00031 boost::shared_ptr<M2 const> msg_;
00032 void handleMessage(const boost::shared_ptr<M2 const> &msg) {
00033 msg_ = msg;
00034 }
00035 };
00036
00037 boost::shared_ptr<LatchedReceiver<M> > receiver_;
00038 M empty_;
00039
00040 public:
00041 LatchedSubscriber();
00042
00043
00044
00045
00046
00047
00048 LatchedSubscriber(ros::NodeHandle &nh,
00049 const std::string &topic,
00050 const ros::TransportHints &transport_hints=ros::TransportHints());
00051
00052
00053
00054
00055 void initialize(ros::NodeHandle &nh,
00056 const std::string &topic,
00057 const ros::TransportHints &transport_hints=ros::TransportHints());
00058
00059 LatchedSubscriber<M>& operator=(const LatchedSubscriber<M> &other);
00060
00061
00062
00063
00064 const boost::shared_ptr<M const>& data() const;
00065 M const * operator->() const;
00066
00067 void reset();
00068 };
00069
00070 template<class M>
00071 LatchedSubscriber<M>::LatchedSubscriber()
00072 {
00073
00074
00075 receiver_ = boost::shared_ptr<LatchedReceiver<M> >(new LatchedReceiver<M>());
00076 }
00077
00078 template<class M>
00079 LatchedSubscriber<M>::LatchedSubscriber(
00080 ros::NodeHandle &nh,
00081 const std::string &topic,
00082 const ros::TransportHints &transport_hints)
00083 {
00084 ROS_WARN("swri_roscpp::LatchedSubscriber has been deprecated. See header for information.");
00085 receiver_ = boost::shared_ptr<LatchedReceiver<M> >(new LatchedReceiver<M>());
00086
00087 Subscriber::operator=(
00088 Subscriber(nh, topic, 1,
00089 &LatchedReceiver<M>::handleMessage, receiver_.get(), transport_hints));
00090 }
00091
00092 template<class M>
00093 void LatchedSubscriber<M>::initialize(
00094 ros::NodeHandle &nh,
00095 const std::string &topic,
00096 const ros::TransportHints &transport_hints)
00097 {
00098 *this = LatchedSubscriber<M>(nh, topic, transport_hints);
00099 }
00100
00101
00102 template<class M>
00103 LatchedSubscriber<M>& LatchedSubscriber<M>::operator=(const LatchedSubscriber<M> &other)
00104 {
00105 Subscriber::operator=(other);
00106 receiver_ = other.receiver_;
00107 return *this;
00108 }
00109
00110 template<class M>
00111 const boost::shared_ptr<M const>& LatchedSubscriber<M>::data() const
00112 {
00113 return receiver_->msg_;
00114 }
00115
00116 template<class M>
00117 M const * LatchedSubscriber<M>::operator->() const
00118 {
00119 if (receiver_->msg_) {
00120 return receiver_->msg_.get();
00121 } else {
00122 return &empty_;
00123 }
00124 }
00125
00126 template<class M>
00127 void LatchedSubscriber<M>::reset()
00128 {
00129 receiver_->msg_.reset();
00130 resetStatistics();
00131 }
00132 }
00133 #endif // SWRI_ROSCPP_SUBSCRIBER_H_
00134