missing_call_to_shutdown_impl.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: David Gossow */
31 
32 /*
33  * Call ros::start() explicitly, but never call ros::shutdown().
34  * ros::shutdown should be called automatically in this case.
35  */
36 
37 #include <cstdlib>
38 #include <ros/ros.h>
39 
40 namespace ros
41 {
42 namespace console
43 {
44 extern bool g_shutting_down;
45 }
46 }
47 
48 namespace
49 {
50 
51 enum TestId
52 {
53  InitOnly = 0,
54  InitAndStart = 1
55 };
56 
57 TestId test_id = InitOnly;
58 
59 void atexitCallback()
60 {
61  bool hasError = false;
62 
63  if (ros::ok())
64  {
65  std::cerr << "ERROR: ros::ok() returned true!" << std::endl;
66  hasError = true;
67  }
68  if (!ros::isShuttingDown())
69  {
70  std::cerr << "ERROR: ros::isShuttingDown() returned false!" << std::endl;
71  hasError = true;
72  }
73  if (ros::isStarted())
74  {
75  std::cerr << "ERROR: ros::isStarted() returned true!" << std::endl;
76  hasError = true;
77  }
78 
79  if (!ros::isInitialized())
80  {
81  std::cerr << "ERROR: ros::isInitialized() returned false, although ros::init was called!" << std::endl;
82  std::cerr << "Due to legacy reasons, it should return true, even after ROS has been de-initialized." << std::endl;
83  hasError = true;
84  }
85 
87  {
88  std::cerr << "ERROR: ros::console::g_shutting_down returned false, but it should have been automatically shut down." << std::endl;
89  hasError = true;
90  }
91 
92  if (hasError)
93  {
94  std::_Exit(1);
95  }
96 }
97 }
98 
99 int
100 main(int argc, char** argv)
101 {
102  if ( argc > 1 )
103  {
104  test_id = static_cast<TestId>(atoi(argv[1]));
105  }
106 
107  // Register atexit callbak which will be executed after ROS has been de-initialized.
108  if (atexit(atexitCallback) != 0)
109  {
110  std::cerr << "Failed to register atexit callback." << std::endl;
111  return 1;
112  }
113 
114  switch (test_id)
115  {
116  case InitOnly:
117  // Test case 0: Call ros::init() explicitly, but never call ros::shutdown().
118  // ros::deInit should be called automatically in this case.
119  ros::init(argc, argv, "missing_call_to_shutdown" );
120  break;
121  case InitAndStart:
122  // Test case 1: Call ros::init() and ros::start() explicitly, but never call ros::shutdown().
123  // ros::shutdown should be called automatically in this case.
124  ros::init(argc, argv, "missing_call_to_shutdown" );
125  ros::start();
126  break;
127  default:
128  std::cerr << "Invalid test id: " << test_id << std::endl;
129  return 1;
130  break;
131  }
132 
133  if (!ros::ok())
134  {
135  std::cerr << "Failed to start ROS." << std::endl;
136  return 1;
137  }
138 
139  return 0;
140 }
atexitCallback
void atexitCallback()
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros
ros.h
main
int main(int argc, char **argv)
Definition: missing_call_to_shutdown_impl.cpp:100
ros::ok
ROSCPP_DECL bool ok()
ros::isInitialized
ROSCPP_DECL bool isInitialized()
ros::isStarted
ROSCPP_DECL bool isStarted()
ros::start
ROSCPP_DECL void start()
ros::console::g_shutting_down
bool g_shutting_down
ros::isShuttingDown
ROSCPP_DECL bool isShuttingDown()


test_roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim, Dirk Thomas , Jacob Perron
autogenerated on Thu Nov 23 2023 04:02:02