1 #ifndef SWRI_ROSCPP_LATCHED_SUBSCRIBER_H_ 2 #define SWRI_ROSCPP_LATCHED_SUBSCRIBER_H_ 49 const std::string &topic,
56 const std::string &topic,
81 const std::string &topic,
84 ROS_WARN(
"swri_roscpp::LatchedSubscriber has been deprecated. See header for information.");
95 const std::string &topic,
113 return receiver_->msg_;
119 if (receiver_->msg_) {
120 return receiver_->msg_.get();
129 receiver_->msg_.reset();
133 #endif // SWRI_ROSCPP_SUBSCRIBER_H_
Subscriber & operator=(const Subscriber &other)
LatchedSubscriber< M > & operator=(const LatchedSubscriber< M > &other)
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)