spinners.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2011, 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: Troy Straszheim */
31 
32 /*
33  * Spinny spinner basic tests.
34 
35  these do NOT ACTUALLY TEST ANYTHING as it is diffcult to restart all
36  of ros in a unit test, and there is no way to test (that I can see
37  right now) that certain error messages are emitted, nor any way to
38  specify that a test should fail or return an error. So this is just
39  a placeholder to be run manually, one test at a time (via
40  --gtest_filter) when the next problem occurs. Those that end with
41  'fail' actually success, but they send a fatal error message that
42  you're trying to spin from multiple threads.
43 */
44 
45 #include <gtest/gtest.h>
46 #include "ros/spinner.h"
47 #include "ros/init.h"
48 #include "ros/node_handle.h"
49 #include <boost/thread.hpp>
50 
51 using namespace ros;
52 
53 int argc_;
54 char** argv_;
55 
57  ROS_INFO("Asking for shutdown");
58  ros::shutdown();
59 }
60 
61 #define DOIT() \
62  ros::init(argc_, argv_, "test_spinners"); \
63  NodeHandle nh; \
64  ros::WallTimer t = nh.createWallTimer(ros::WallDuration(2.0), \
65  &fire_shutdown); \
66 
67 TEST(Spinners, spin)
68 {
69  DOIT();
70  ros::spin(); // will block until ROS shutdown
71 }
72 
73 TEST(Spinners, spinfail)
74 {
75  DOIT();
76  boost::thread th(boost::bind(&ros::spin));
77  ros::WallDuration(0.1).sleep(); // wait for thread to be started
78 
79  EXPECT_THROW(ros::spin(), std::runtime_error);
80 
82  EXPECT_THROW(ros::spin(ss), std::runtime_error);
83  EXPECT_THROW(ss.spin(), std::runtime_error);
84 
86  EXPECT_THROW(ros::spin(ms), std::runtime_error);
87  EXPECT_THROW(ms.spin(), std::runtime_error);
88 
89  AsyncSpinner as(2);
90  EXPECT_THROW(as.start(), std::runtime_error);
91 
93 }
94 
95 TEST(Spinners, singlefail)
96 {
97  DOIT();
99  boost::thread th(boost::bind(&ros::spin, ss));
100  ros::WallDuration(0.1).sleep(); // wait for thread to be started
101 
102  EXPECT_THROW(ros::spin(), std::runtime_error);
103 
105  EXPECT_THROW(ros::spin(ss2), std::runtime_error);
106  EXPECT_THROW(ss2.spin(), std::runtime_error);
107 
109  EXPECT_THROW(ros::spin(ms), std::runtime_error);
110  EXPECT_THROW(ms.spin(), std::runtime_error);
111 
112  AsyncSpinner as(2);
113  EXPECT_THROW(as.start(), std::runtime_error);
114 
116 }
117 
118 TEST(Spinners, multi)
119 {
120  DOIT();
122  ros::spin(ms); // will block until ROS shutdown
123 }
124 
125 TEST(Spinners, multifail)
126 {
127  DOIT();
129  boost::thread th(boost::bind(&ros::spin, ms));
130  ros::WallDuration(0.1).sleep(); // wait for thread to be started
131 
133  EXPECT_THROW(ros::spin(ss2), std::runtime_error);
134  EXPECT_THROW(ss2.spin(), std::runtime_error);
135 
136  // running another multi-threaded spinner is allowed
138  ros::spin(ms2); // will block until ROS shutdown
139 }
140 
141 TEST(Spinners, async)
142 {
143  DOIT();
144  AsyncSpinner as1(2);
145  as1.start();
146 
147  // running another AsyncSpinner is allowed
148  AsyncSpinner as2(2);
149  as2.start();
150  as2.stop();
151 
153  EXPECT_THROW(ros::spin(ss), std::runtime_error);
154  EXPECT_THROW(ss.spin(), std::runtime_error);
155 
156  // running a multi-threaded spinner is allowed
158  ros::spin(ms); // will block until ROS shutdown
159 
161 }
162 
163 
164 int
165 main(int argc, char** argv)
166 {
167  testing::InitGoogleTest(&argc, argv);
168  argc_ = argc;
169  argv_ = argv;
170  return RUN_ALL_TESTS();
171 }
int argc_
Definition: spinners.cpp:53
virtual void spin(CallbackQueue *queue=0)
TEST(Spinners, spin)
Definition: spinners.cpp:67
int main(int argc, char **argv)
Definition: spinners.cpp:165
void fire_shutdown(const ros::WallTimerEvent &)
Definition: spinners.cpp:56
bool sleep() const
#define ROS_INFO(...)
ROSCPP_DECL void spin()
char ** argv_
Definition: spinners.cpp:54
ROSCPP_DECL void shutdown()
#define DOIT()
Definition: spinners.cpp:61
ROSCPP_DECL void waitForShutdown()


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