35 #include <gtest/gtest.h> 38 #include "roscpp/Logger.h" 43 typedef roscpp::Logger
Msg;
150 MsgPtr msg(boost::make_shared<Msg>());
156 ASSERT_EQ(msg.get(), h.
msg_.get());
167 MsgPtr msg(boost::make_shared<Msg>());
173 ASSERT_TRUE(h2.
msg_);
174 EXPECT_NE(msg.get(), h.
msg_.get());
175 EXPECT_NE(msg.get(), h2.
msg_.get());
176 EXPECT_NE(h.
msg_.get(), h2.
msg_.get());
187 MsgPtr msg(boost::make_shared<Msg>());
193 ASSERT_TRUE(h2.
msg_);
194 EXPECT_NE(msg.get(), h.
msg_.get());
195 EXPECT_NE(msg.get(), h2.
msg_.get());
196 EXPECT_NE(h.
msg_.get(), h2.
msg_.get());
200 int main(
int argc,
char **argv){
201 testing::InitGoogleTest(&argc, argv);
203 ros::init(argc, argv,
"test_subscriber");
206 return RUN_ALL_TESTS();
void cb(const MsgConstPtr &msg)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void publish(const boost::shared_ptr< M > &message) const
roscpp::LoggerConstPtr MsgConstPtr
void cb(const MsgConstPtr &)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
int main(int argc, char **argv)
void cb(const MsgPtr &msg)
Chains a dynamic number of simple filters together. Allows retrieval of filters by index after they a...
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
Subscribe to a topic.
size_t addFilter(F *filter)
Add a filter to this chain, by bare pointer. Returns the index of that filter in the chain...
void unsubscribe()
Force immediate unsubscription of this subscriber from its topic.
ROSCPP_DECL void spinOnce()
Connection registerCallback(const C &callback)
Register a callback to be called when this filter has passed.