38 #include <gtest/gtest.h> 44 #include "test_roscpp/TestEmpty.h" 49 void callback(
const test_roscpp::TestEmptyConstPtr& msg)
59 void callback(
const test_roscpp::TestEmptyPtr& msg)
67 TEST(NonConstSubscriptions, oneNonConstSubscriber)
74 test_roscpp::TestEmptyPtr msg(boost::make_shared<test_roscpp::TestEmpty>());
82 TEST(NonConstSubscriptions, oneConstOneNonConst)
91 test_roscpp::TestEmptyPtr msg(boost::make_shared<test_roscpp::TestEmpty>());
100 TEST(NonConstSubscriptions, twoNonConst)
109 test_roscpp::TestEmptyPtr msg(boost::make_shared<test_roscpp::TestEmpty>());
117 TEST(NonConstSubscriptions, twoConst)
126 test_roscpp::TestEmptyPtr msg(boost::make_shared<test_roscpp::TestEmpty>());
135 int main(
int argc,
char** argv)
137 testing::InitGoogleTest(&argc, argv);
138 ros::init(argc, argv,
"intraprocess_subscriptions");
142 return RUN_ALL_TESTS();
test_roscpp::TestEmptyConstPtr message_
int main(int argc, char **argv)
void publish(const boost::shared_ptr< M > &message) const
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)
TEST(NonConstSubscriptions, oneNonConstSubscriber)
test_roscpp::TestEmptyPtr message_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void callback(const test_roscpp::TestEmptyPtr &msg)
ROSCPP_DECL void spinOnce()
void callback(const test_roscpp::TestEmptyConstPtr &msg)