handles.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 /* Author: Josh Faust */
31 
32 /*
33  * Test handles
34  */
35 
36 #include <string>
37 #include <sstream>
38 #include <fstream>
39 
40 #include <gtest/gtest.h>
41 
42 #include <time.h>
43 #include <stdlib.h>
44 
45 #include "ros/ros.h"
46 #include "ros/callback_queue.h"
47 #include <test_roscpp/TestArray.h>
48 #include <test_roscpp/TestStringString.h>
49 
50 #include <boost/thread.hpp>
51 
52 using namespace ros;
53 using namespace test_roscpp;
54 
55 TEST(RoscppHandles, nodeHandleConstructionDestruction)
56 {
57  {
58  ASSERT_FALSE(ros::isStarted());
59 
60  ros::NodeHandle n1;
61  ASSERT_TRUE(ros::isStarted());
62 
63  {
64  ros::NodeHandle n2;
65  ASSERT_TRUE(ros::isStarted());
66 
67  {
68  ros::NodeHandle n3(n2);
69  ASSERT_TRUE(ros::isStarted());
70 
71  {
72  ros::NodeHandle n4 = n3;
73  ASSERT_TRUE(ros::isStarted());
74  }
75  }
76  }
77 
78  ASSERT_TRUE(ros::isStarted());
79  }
80 
81  ASSERT_FALSE(ros::isStarted());
82 
83  {
85  ASSERT_TRUE(ros::isStarted());
86  }
87 
88  ASSERT_FALSE(ros::isStarted());
89 }
90 
91 TEST(RoscppHandles, nodeHandleParentWithRemappings)
92 {
93  ros::M_string remappings;
94  remappings["a"] = "b";
95  remappings["c"] = "d";
96  ros::NodeHandle n1("", remappings);
97 
98  // sanity checks
99  EXPECT_STREQ(n1.resolveName("a").c_str(), "/b");
100  EXPECT_STREQ(n1.resolveName("/a").c_str(), "/b");
101  EXPECT_STREQ(n1.resolveName("c").c_str(), "/d");
102  EXPECT_STREQ(n1.resolveName("/c").c_str(), "/d");
103 
104  ros::NodeHandle n2(n1, "my_ns");
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");
109 
110  ros::NodeHandle n3(n2);
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");
115 
116  ros::NodeHandle n4;
117  n4 = n3;
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");
122 }
123 
124 int32_t g_recv_count = 0;
125 void subscriberCallback(const test_roscpp::TestArray::ConstPtr&)
126 {
127  ++g_recv_count;
128 }
129 
131 {
132 public:
134  : recv_count_(0)
135  {}
136 
137  void callback(const test_roscpp::TestArray::ConstPtr&)
138  {
139  ++recv_count_;
140  }
141 
142  int32_t recv_count_;
143 };
144 
145 TEST(RoscppHandles, subscriberValidity)
146 {
147  ros::NodeHandle n;
148 
149  ros::Subscriber sub;
150  ASSERT_FALSE(sub);
151 
152  sub = n.subscribe("test", 0, subscriberCallback);
153  ASSERT_TRUE(sub);
154 }
155 
156 TEST(RoscppHandles, subscriberDestructionMultipleCallbacks)
157 {
158  ros::NodeHandle n;
159  ros::Publisher pub = n.advertise<test_roscpp::TestArray>("test", 0);
160  test_roscpp::TestArray msg;
161 
162  {
163  SubscribeHelper helper;
164  ros::Subscriber sub_class = n.subscribe("test", 0, &SubscribeHelper::callback, &helper);
165 
166  ros::Duration d(0.05);
167  int32_t last_class_count = helper.recv_count_;
168  while (last_class_count == helper.recv_count_)
169  {
170  pub.publish(msg);
171  ros::spinOnce();
172  d.sleep();
173  }
174 
175  int32_t last_fn_count = g_recv_count;
176  {
177  ros::Subscriber sub_fn = n.subscribe("test", 0, subscriberCallback);
178 
179  ASSERT_TRUE(sub_fn != sub_class);
180 
181  last_fn_count = g_recv_count;
182  while (last_fn_count == g_recv_count)
183  {
184  pub.publish(msg);
185  ros::spinOnce();
186  d.sleep();
187  }
188  }
189 
190  last_fn_count = g_recv_count;
191  last_class_count = helper.recv_count_;
192  while (last_class_count == helper.recv_count_)
193  {
194  pub.publish(msg);
195  ros::spinOnce();
196  d.sleep();
197  }
198  d.sleep();
199 
200  ASSERT_EQ(last_fn_count, g_recv_count);
201  }
202 }
203 
204 TEST(RoscppHandles, subscriberSpinAfterSubscriberShutdown)
205 {
206  ros::NodeHandle n;
207  ros::Publisher pub = n.advertise<test_roscpp::TestArray>("test", 0);
208  test_roscpp::TestArray msg;
209 
210  int32_t last_fn_count = g_recv_count;
211 
212  {
213  ros::Subscriber sub_fn = n.subscribe("test", 0, subscriberCallback);
214 
215  last_fn_count = g_recv_count;
216  for (int i = 0; i < 10; ++i)
217  {
218  pub.publish(msg);
219  }
220 
221  ros::WallDuration(0.1).sleep();
222  }
223 
224  ros::spinOnce();
225 
226  ASSERT_EQ(last_fn_count, g_recv_count);
227 }
228 
229 TEST(RoscppHandles, subscriberGetNumPublishers)
230 {
231  ros::NodeHandle n;
232  ros::Publisher pub = n.advertise<test_roscpp::TestArray>("test", 0);
233 
234  ros::Subscriber sub = n.subscribe("test", 0, subscriberCallback);
235 
237  while (sub.getNumPublishers() < 1 && (ros::WallTime::now() - begin < ros::WallDuration(1)))
238  {
239  ros::spinOnce();
240  ros::WallDuration(0.1).sleep();
241  }
242 
243  ASSERT_EQ(sub.getNumPublishers(), 1ULL);
244 }
245 
246 TEST(RoscppHandles, subscriberCopy)
247 {
248  ros::NodeHandle n;
249 
250  g_recv_count = 0;
251 
252  {
253  ros::Subscriber sub1 = n.subscribe("/test", 0, subscriberCallback);
254 
255  {
256  ros::Subscriber sub2 = sub1;
257 
258  {
259  ros::Subscriber sub3(sub2);
260 
261  ASSERT_TRUE(sub3 == sub2);
262 
263  V_string topics;
265  ASSERT_TRUE(std::find(topics.begin(), topics.end(), "/test") != topics.end());
266  }
267 
268  ASSERT_TRUE(sub2 == sub1);
269 
270  V_string topics;
272  ASSERT_TRUE(std::find(topics.begin(), topics.end(), "/test") != topics.end());
273  }
274 
275  V_string topics;
277  ASSERT_TRUE(std::find(topics.begin(), topics.end(), "/test") != topics.end());
278  }
279 
280  V_string topics;
282  ASSERT_TRUE(std::find(topics.begin(), topics.end(), "/test") == topics.end());
283 }
284 
285 TEST(RoscppHandles, publisherCopy)
286 {
287  ros::NodeHandle n;
288 
289  g_recv_count = 0;
290 
291  {
292  ros::Publisher pub1 = n.advertise<test_roscpp::TestArray>("/test", 0);
293 
294  {
295  ros::Publisher pub2 = pub1;
296 
297  {
298  ros::Publisher pub3(pub2);
299 
300  ASSERT_TRUE(pub3 == pub2);
301 
302  V_string topics;
304  ASSERT_TRUE(std::find(topics.begin(), topics.end(), "/test") != topics.end());
305  }
306 
307  ASSERT_TRUE(pub2 == pub1);
308 
309  V_string topics;
311  ASSERT_TRUE(std::find(topics.begin(), topics.end(), "/test") != topics.end());
312  }
313 
314  V_string topics;
316  ASSERT_TRUE(std::find(topics.begin(), topics.end(), "/test") != topics.end());
317  }
318 
319  V_string topics;
321  ASSERT_TRUE(std::find(topics.begin(), topics.end(), "/test") == topics.end());
322 }
323 
324 TEST(RoscppHandles, publisherMultiple)
325 {
326  ros::NodeHandle n;
327 
328  g_recv_count = 0;
329 
330  {
331  ros::Publisher pub1 = n.advertise<test_roscpp::TestArray>("/test", 0);
332 
333  {
334  ros::Publisher pub2 = n.advertise<test_roscpp::TestArray>("/test", 0);
335 
336  ASSERT_TRUE(pub1 != pub2);
337 
338  V_string topics;
340  ASSERT_TRUE(std::find(topics.begin(), topics.end(), "/test") != topics.end());
341  }
342 
343  V_string topics;
345  ASSERT_TRUE(std::find(topics.begin(), topics.end(), "/test") != topics.end());
346  }
347 
348  V_string topics;
350  ASSERT_TRUE(std::find(topics.begin(), topics.end(), "/test") == topics.end());
351 }
352 
353 bool serviceCallback(TestStringString::Request&, TestStringString::Response&)
354 {
355  return true;
356 }
357 
359 {
360  while (queue->isEnabled())
361  {
362  queue->callAvailable(ros::WallDuration(0.1));
363  }
364 }
365 
366 TEST(RoscppHandles, serviceAdv)
367 {
368  ros::NodeHandle n;
369  TestStringString t;
370 
371  ros::CallbackQueue queue;
372  n.setCallbackQueue(&queue);
373  boost::thread th(boost::bind(pump, &queue));
374  {
376 
377  EXPECT_TRUE(ros::service::call("/test_srv", t));
378  }
379 
380  queue.disable();
381  th.join();
382 
383  ASSERT_FALSE(ros::service::call("/test_srv", t));
384 }
385 
386 TEST(RoscppHandles, serviceAdvCopy)
387 {
388  ros::NodeHandle n;
389  TestStringString t;
390 
391  ros::CallbackQueue queue;
392  n.setCallbackQueue(&queue);
393  boost::thread th(boost::bind(pump, &queue));
394 
395  {
396  ros::ServiceServer srv1 = n.advertiseService("/test_srv", serviceCallback);
397 
398  {
399  ros::ServiceServer srv2 = srv1;
400 
401  {
402  ros::ServiceServer srv3(srv2);
403 
404  ASSERT_TRUE(srv3 == srv2);
405 
406  EXPECT_TRUE(ros::service::call("/test_srv", t));
407  }
408 
409  ASSERT_TRUE(srv2 == srv1);
410 
411  EXPECT_TRUE(ros::service::call("/test_srv", t));
412  }
413 
414  EXPECT_TRUE(ros::service::call("/test_srv", t));
415  }
416 
417  ASSERT_FALSE(ros::service::call("/test_srv", t));
418 
419  queue.disable();
420  th.join();
421 }
422 
423 TEST(RoscppHandles, serviceAdvMultiple)
424 {
425  ros::NodeHandle n;
426 
428  ros::ServiceServer srv2 = n.advertiseService("/test_srv", serviceCallback);
429  ASSERT_TRUE(srv);
430  ASSERT_FALSE(srv2);
431 
432  ASSERT_TRUE(srv != srv2);
433 }
434 
435 int32_t g_sub_count = 0;
437 {
438  ++g_sub_count;
439 }
440 
441 TEST(RoscppHandles, trackedObjectWithAdvertiseSubscriberCallback)
442 {
443  ros::NodeHandle n;
444 
445  boost::shared_ptr<char> tracked(boost::make_shared<char>());
446 
447  ros::Publisher pub = n.advertise<test_roscpp::TestArray>("/test", 0, connectedCallback, SubscriberStatusCallback(), tracked);
448 
449  g_recv_count = 0;
450  g_sub_count = 0;
451  ros::Subscriber sub = n.subscribe("/test", 0, subscriberCallback);
452 
453  Duration d(0.01);
454  while (g_sub_count == 0)
455  {
456  d.sleep();
457  ros::spinOnce();
458  }
459  ASSERT_EQ(g_sub_count, 1);
460 
461  sub.shutdown();
462 
463  tracked.reset();
464  sub = n.subscribe("/test", 0, subscriberCallback);
465 
466  Duration d2(0.01);
467  for (int i = 0; i < 10; ++i)
468  {
469  d2.sleep();
470  ros::spinOnce();
471  }
472 
473  ASSERT_EQ(g_sub_count, 1);
474 }
475 
476 TEST(RoscppHandles, spinAfterHandleShutdownWithAdvertiseSubscriberCallback)
477 {
478  ros::NodeHandle n;
479  ros::Publisher pub = n.advertise<test_roscpp::TestArray>("/test", 0, connectedCallback, SubscriberStatusCallback());
480 
481  g_sub_count = 0;
482  ros::Subscriber sub = n.subscribe("/test", 0, subscriberCallback);
483 
484  while (pub.getNumSubscribers() == 0)
485  {
486  ros::WallDuration(0.01).sleep();
487  }
488 
489  pub.shutdown();
490 
491  ros::spinOnce();
492 
493  ASSERT_EQ(g_sub_count, 0);
494 }
495 
496 TEST(RoscppHandles, multiplePublishersWithSubscriberConnectCallback)
497 {
498  ros::NodeHandle n;
499  ros::Publisher pub = n.advertise<test_roscpp::TestArray>("/test", 0, connectedCallback, SubscriberStatusCallback());
500 
501  g_sub_count = 0;
502  ros::Subscriber sub = n.subscribe("/test", 0, subscriberCallback);
503 
504  while (g_sub_count == 0)
505  {
506  ros::WallDuration(0.01).sleep();
507  ros::spinOnce();
508  }
509 
510  ASSERT_EQ(g_sub_count, 1);
511  g_sub_count = 0;
512 
513  ros::Publisher pub2 = n.advertise<test_roscpp::TestArray>("/test", 0, connectedCallback, SubscriberStatusCallback());
514  ros::spinOnce();
515 
516  ASSERT_EQ(g_sub_count, 1);
517 }
518 
520 {
521 public:
522  bool serviceCallback(TestStringString::Request&, TestStringString::Response&)
523  {
524  return true;
525  }
526 };
527 
528 TEST(RoscppHandles, trackedObjectWithServiceCallback)
529 {
530  ros::NodeHandle n;
531 
532  ros::CallbackQueue queue;
533  n.setCallbackQueue(&queue);
534  boost::thread th(boost::bind(pump, &queue));
535 
536  boost::shared_ptr<ServiceClass> tracked(boost::make_shared<ServiceClass>());
537  ros::ServiceServer srv = n.advertiseService("/test_srv", &ServiceClass::serviceCallback, tracked);
538 
539  TestStringString t;
540  EXPECT_TRUE(ros::service::call("/test_srv", t));
541 
542  tracked.reset();
543 
544  ASSERT_FALSE(ros::service::call("/test_srv", t));
545 
546  queue.disable();
547  th.join();
548 }
549 
550 TEST(RoscppHandles, trackedObjectWithSubscriptionCallback)
551 {
552  ros::NodeHandle n;
553 
554  boost::shared_ptr<SubscribeHelper> tracked(boost::make_shared<SubscribeHelper>());
555 
556  g_recv_count = 0;
557  ros::Subscriber sub = n.subscribe("/test", 0, &SubscribeHelper::callback, tracked);
558 
559  ros::Publisher pub = n.advertise<test_roscpp::TestArray>("/test", 0);
560 
561  test_roscpp::TestArray msg;
562  Duration d(0.01);
563  while (tracked->recv_count_ == 0)
564  {
565  pub.publish(msg);
566  d.sleep();
567  ros::spinOnce();
568  }
569  ASSERT_GE(tracked->recv_count_, 1);
570 
571  tracked.reset();
572 
573  pub.publish(msg);
574  Duration d2(0.01);
575  for (int i = 0; i < 10; ++i)
576  {
577  d2.sleep();
578  ros::spinOnce();
579  }
580 }
581 
582 TEST(RoscppHandles, nodeHandleNames)
583 {
584  ros::NodeHandle n1;
585  EXPECT_STREQ(n1.resolveName("blah").c_str(), "/blah");
586 
587  try
588  {
589  n1.resolveName("~blah");
590  FAIL();
591  }
593  {
594  }
595 
596  ros::NodeHandle n2("internal_ns");
597  EXPECT_STREQ(n2.resolveName("blah").c_str(), "/internal_ns/blah");
598 
599  ros::NodeHandle n3(n2, "2");
600  EXPECT_STREQ(n3.resolveName("blah").c_str(), "/internal_ns/2/blah");
601 
602  ros::NodeHandle n4("~");
603  EXPECT_STREQ(n4.resolveName("blah").c_str(), (ros::this_node::getName() + "/blah").c_str());
604 
605  try {
606  ros::NodeHandle n5(n2, "illegal_name!!!");
607  FAIL();
608  } catch (ros::InvalidNameException&) { }
609 
610 }
611 
612 TEST(RoscppHandles, nodeHandleShutdown)
613 {
614  ros::NodeHandle n;
615 
616  ros::Subscriber sub = n.subscribe("/test", 0, subscriberCallback);
617  ros::Publisher pub = n.advertise<test_roscpp::TestArray>("/test", 0);
619 
620  n.shutdown();
621 
622  ASSERT_FALSE(pub);
623  ASSERT_FALSE(sub);
624  ASSERT_FALSE(srv);
625 }
626 
627 int main(int argc, char** argv)
628 {
629  testing::InitGoogleTest(&argc, argv);
630  ros::init(argc, argv, "test_handles");
631 
632  return RUN_ALL_TESTS();
633 }
634 
d
int32_t g_sub_count
Definition: handles.cpp:435
bool serviceCallback(TestStringString::Request &, TestStringString::Response &)
Definition: handles.cpp:353
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 &)
Definition: handles.cpp:522
bool call(const std::string &service_name, MReq &req, MRes &res)
bool sleep() const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int32_t g_recv_count
Definition: handles.cpp:124
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 &)
Definition: handles.cpp:436
int32_t recv_count_
Definition: handles.cpp:142
std::map< std::string, std::string > M_string
std::vector< std::string > V_string
bool sleep() const
ROSCPP_DECL void getSubscribedTopics(V_string &topics)
void setCallbackQueue(CallbackQueueInterface *queue)
void callback(const test_roscpp::TestArray::ConstPtr &)
Definition: handles.cpp:137
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
TEST(RoscppHandles, nodeHandleConstructionDestruction)
Definition: handles.cpp:55
uint32_t getNumSubscribers() const
static WallTime now()
ROSCPP_DECL bool isStarted()
ROSCPP_DECL void getAdvertisedTopics(V_string &topics)
int main(int argc, char **argv)
Definition: handles.cpp:627
void subscriberCallback(const test_roscpp::TestArray::ConstPtr &)
Definition: handles.cpp:125
void pump(ros::CallbackQueue *queue)
Definition: handles.cpp:358
ROSCPP_DECL void spinOnce()
ros::WallTime t


test_roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim, Dirk Thomas
autogenerated on Mon Nov 2 2020 03:52:46