34 #include <gtest/gtest.h> 39 #include "test_roscpp/TestEmpty.h" 40 #include "test_roscpp/TestArray.h" 42 #include <std_srvs/Empty.h> 52 namespace message_traits
58 static const char*
value() {
return "*"; }
65 static const char*
value() {
return "*"; }
76 namespace serialization
81 template<
typename Stream,
typename T>
107 TEST(SubscribeStar, simpleSubFirstIntra)
120 EXPECT_EQ(h.
count, 1U);
123 TEST(SubscribeStar, simplePubFirstIntra)
131 EXPECT_EQ(sub.getNumPublishers(), 1U);
136 EXPECT_EQ(h.
count, 1U);
144 TEST(SubscribeStar, multipleSubsStarFirstIntra)
157 pub = nh.
advertise<test_roscpp::TestArray>(
"test_star_intra", 0);
163 TEST(SubscribeStar, multipleSubsConcreteFirstIntra)
176 pub = nh.
advertise<test_roscpp::TestArray>(
"test_star_intra", 0);
182 TEST(SubscribeStar, multipleShutdownConcreteIntra)
195 pub = nh.
advertise<test_roscpp::TestArray>(
"test_star_intra", 0);
200 TEST(SubscribeStar, simpleInter)
210 EXPECT_GT(h.
count, 0U);
213 TEST(SubscribeStar, simpleInterUDP)
223 EXPECT_GT(h.
count, 0U);
227 TEST(SubscribeStar, switchTypeInter)
276 int main(
int argc,
char** argv)
278 testing::InitGoogleTest(&argc, argv);
281 return RUN_ALL_TESTS();
static const char * value()
boost::shared_ptr< AnyMessage > AnyMessagePtr
void publish(const boost::shared_ptr< M > &message) const
static const char * value(const AnyMessage &)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
static const char * value(const AnyMessage &)
#define ROS_DECLARE_ALLINONE_SERIALIZER
static void allInOne(Stream, T)
bool call(const std::string &service_name, MReq &req, MRes &res)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
uint32_t getNumPublishers() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void emptyCallback(const test_roscpp::TestEmptyConstPtr &)
static const char * value()
void cb(const AnyMessageConstPtr &)
TEST(SubscribeStar, simpleSubFirstIntra)
uint32_t getNumSubscribers() const
ROSCPP_DECL void spinOnce()
boost::shared_ptr< AnyMessage const > AnyMessageConstPtr
int main(int argc, char **argv)