40 #include <gtest/gtest.h> 47 #include <test_roscpp/TestArray.h> 48 #include <test_roscpp/TestStringString.h> 50 #include <boost/thread.hpp> 55 TEST(RoscppHandles, nodeHandleConstructionDestruction)
91 TEST(RoscppHandles, nodeHandleParentWithRemappings)
94 remappings[
"a"] =
"b";
95 remappings[
"c"] =
"d";
105 EXPECT_STREQ(n2.resolveName(
"a").c_str(),
"/my_ns/a");
106 EXPECT_STREQ(n2.resolveName(
"/a").c_str(),
"/b");
107 EXPECT_STREQ(n2.resolveName(
"c").c_str(),
"/my_ns/c");
108 EXPECT_STREQ(n2.resolveName(
"/c").c_str(),
"/d");
111 EXPECT_STREQ(n3.resolveName(
"a").c_str(),
"/my_ns/a");
112 EXPECT_STREQ(n3.resolveName(
"/a").c_str(),
"/b");
113 EXPECT_STREQ(n3.resolveName(
"c").c_str(),
"/my_ns/c");
114 EXPECT_STREQ(n3.resolveName(
"/c").c_str(),
"/d");
118 EXPECT_STREQ(n4.resolveName(
"a").c_str(),
"/my_ns/a");
119 EXPECT_STREQ(n4.resolveName(
"/a").c_str(),
"/b");
120 EXPECT_STREQ(n4.resolveName(
"c").c_str(),
"/my_ns/c");
121 EXPECT_STREQ(n4.resolveName(
"/c").c_str(),
"/d");
137 void callback(
const test_roscpp::TestArray::ConstPtr&)
145 TEST(RoscppHandles, subscriberValidity)
156 TEST(RoscppHandles, subscriberDestructionMultipleCallbacks)
160 test_roscpp::TestArray msg;
179 ASSERT_TRUE(sub_fn != sub_class);
204 TEST(RoscppHandles, subscriberSpinAfterSubscriberShutdown)
208 test_roscpp::TestArray msg;
216 for (
int i = 0; i < 10; ++i)
229 TEST(RoscppHandles, subscriberGetNumPublishers)
243 ASSERT_EQ(sub.getNumPublishers(), 1ULL);
246 TEST(RoscppHandles, subscriberCopy)
261 ASSERT_TRUE(sub3 == sub2);
265 ASSERT_TRUE(std::find(topics.begin(), topics.end(),
"/test") != topics.end());
268 ASSERT_TRUE(sub2 == sub1);
272 ASSERT_TRUE(std::find(topics.begin(), topics.end(),
"/test") != topics.end());
277 ASSERT_TRUE(std::find(topics.begin(), topics.end(),
"/test") != topics.end());
282 ASSERT_TRUE(std::find(topics.begin(), topics.end(),
"/test") == topics.end());
285 TEST(RoscppHandles, publisherCopy)
300 ASSERT_TRUE(pub3 == pub2);
304 ASSERT_TRUE(std::find(topics.begin(), topics.end(),
"/test") != topics.end());
307 ASSERT_TRUE(pub2 == pub1);
311 ASSERT_TRUE(std::find(topics.begin(), topics.end(),
"/test") != topics.end());
316 ASSERT_TRUE(std::find(topics.begin(), topics.end(),
"/test") != topics.end());
321 ASSERT_TRUE(std::find(topics.begin(), topics.end(),
"/test") == topics.end());
324 TEST(RoscppHandles, publisherMultiple)
336 ASSERT_TRUE(pub1 != pub2);
340 ASSERT_TRUE(std::find(topics.begin(), topics.end(),
"/test") != topics.end());
345 ASSERT_TRUE(std::find(topics.begin(), topics.end(),
"/test") != topics.end());
350 ASSERT_TRUE(std::find(topics.begin(), topics.end(),
"/test") == topics.end());
366 TEST(RoscppHandles, serviceAdv)
373 boost::thread th(boost::bind(
pump, &queue));
386 TEST(RoscppHandles, serviceAdvCopy)
393 boost::thread th(boost::bind(
pump, &queue));
404 ASSERT_TRUE(srv3 == srv2);
409 ASSERT_TRUE(srv2 == srv1);
423 TEST(RoscppHandles, serviceAdvMultiple)
432 ASSERT_TRUE(srv != srv2);
441 TEST(RoscppHandles, trackedObjectWithAdvertiseSubscriberCallback)
467 for (
int i = 0; i < 10; ++i)
476 TEST(RoscppHandles, spinAfterHandleShutdownWithAdvertiseSubscriberCallback)
493 ASSERT_EQ(g_sub_count, 0);
496 TEST(RoscppHandles, multiplePublishersWithSubscriberConnectCallback)
504 while (g_sub_count == 0)
510 ASSERT_EQ(g_sub_count, 1);
516 ASSERT_EQ(g_sub_count, 1);
528 TEST(RoscppHandles, trackedObjectWithServiceCallback)
534 boost::thread th(boost::bind(
pump, &queue));
550 TEST(RoscppHandles, trackedObjectWithSubscriptionCallback)
561 test_roscpp::TestArray msg;
563 while (tracked->recv_count_ == 0)
569 ASSERT_GE(tracked->recv_count_, 1);
575 for (
int i = 0; i < 10; ++i)
582 TEST(RoscppHandles, nodeHandleNames)
585 EXPECT_STREQ(n1.
resolveName(
"blah").c_str(),
"/blah");
597 EXPECT_STREQ(n2.
resolveName(
"blah").c_str(),
"/internal_ns/blah");
600 EXPECT_STREQ(n3.resolveName(
"blah").c_str(),
"/internal_ns/2/blah");
612 TEST(RoscppHandles, nodeHandleShutdown)
627 int main(
int argc,
char** argv)
629 testing::InitGoogleTest(&argc, argv);
632 return RUN_ALL_TESTS();
bool serviceCallback(TestStringString::Request &, TestStringString::Response &)
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
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())
std::string resolveName(const std::string &name, bool remap=true) const
bool serviceCallback(TestStringString::Request &, TestStringString::Response &)
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)
ROSCPP_DECL const std::string & getName()
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
void connectedCallback(const ros::SingleSubscriberPublisher &)
std::map< std::string, std::string > M_string
std::vector< std::string > V_string
ROSCPP_DECL void getSubscribedTopics(V_string &topics)
void setCallbackQueue(CallbackQueueInterface *queue)
void callback(const test_roscpp::TestArray::ConstPtr &)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
TEST(RoscppHandles, nodeHandleConstructionDestruction)
uint32_t getNumSubscribers() const
ROSCPP_DECL bool isStarted()
ROSCPP_DECL void getAdvertisedTopics(V_string &topics)
int main(int argc, char **argv)
void subscriberCallback(const test_roscpp::TestArray::ConstPtr &)
void pump(ros::CallbackQueue *queue)
ROSCPP_DECL void spinOnce()