diff --git a/clients/roscpp/src/libros/init.cpp b/clients/roscpp/src/libros/init.cpp
index 23904cd8f0..05af5a88e3 100644
--- a/clients/roscpp/src/libros/init.cpp
+++ b/clients/roscpp/src/libros/init.cpp
@@ -99,6 +99,7 @@ static CallbackQueuePtr g_internal_callback_queue;
static bool g_initialized = false;
static bool g_started = false;
static bool g_atexit_registered = false;
+static bool g_shutdown_registered = false;
static boost::mutex g_start_mutex;
static bool g_ok = false;
static uint32_t g_init_options = 0;
@@ -408,6 +409,16 @@ void start()
if (g_shutting_down) goto end;
g_internal_queue_thread = boost::thread(internalCallbackQueueThreadFunc);
+
+ // Ensure that shutdown() is always called when the program exits,
+ // but before singletons get destroyed, so that the internal queue thread is joined first
+ // and cannot access destroyed singletons.
+ if (!g_shutdown_registered)
+ {
+ g_shutdown_registered = true;
+ atexit(shutdown);
+ }
+
getGlobalCallbackQueue()->enable();
ROSCPP_LOG_DEBUG("Started node [%s], pid [%d], bound on [%s], xmlrpc port [%d], tcpros port [%d], using [%s] time",
diff --git a/test/test_roscpp/test/CMakeLists.txt b/test/test_roscpp/test/CMakeLists.txt
index 122f9d5b6b..2aaf20c3b2 100644
--- a/test/test_roscpp/test/CMakeLists.txt
+++ b/test/test_roscpp/test/CMakeLists.txt
@@ -92,6 +92,10 @@ add_rostest(launch/service_call_zombie.xml)
# Repeatedly call ros::init() and ros::fini()
add_rostest(launch/multiple_init_fini.xml)
+# Check that ros::shutdown is automatically called
+# if ros::start has been called explcitly
+add_rostest(launch/missing_call_to_shutdown.xml)
+
# Test node inspection functionality
add_rostest(launch/inspection.xml)
diff --git a/test/test_roscpp/test/launch/missing_call_to_shutdown.xml b/test/test_roscpp/test/launch/missing_call_to_shutdown.xml
new file mode 100644
index 0000000000..ff2f4c43dd
--- /dev/null
+++ b/test/test_roscpp/test/launch/missing_call_to_shutdown.xml
@@ -0,0 +1,3 @@
+
+
+
diff --git a/test/test_roscpp/test/src/CMakeLists.txt b/test/test_roscpp/test/src/CMakeLists.txt
index 7d5c324314..eaa5a7955e 100644
--- a/test/test_roscpp/test/src/CMakeLists.txt
+++ b/test/test_roscpp/test/src/CMakeLists.txt
@@ -89,6 +89,12 @@ add_dependencies(${PROJECT_NAME}-service_exception ${std_srvs_EXPORTED_TARGETS})
add_executable(${PROJECT_NAME}-multiple_init_fini EXCLUDE_FROM_ALL multiple_init_fini.cpp)
target_link_libraries(${PROJECT_NAME}-multiple_init_fini ${GTEST_LIBRARIES} ${catkin_LIBRARIES})
+add_executable(${PROJECT_NAME}-missing_call_to_shutdown_impl EXCLUDE_FROM_ALL missing_call_to_shutdown_impl.cpp)
+target_link_libraries(${PROJECT_NAME}-missing_call_to_shutdown_impl ${catkin_LIBRARIES})
+
+add_executable(${PROJECT_NAME}-missing_call_to_shutdown EXCLUDE_FROM_ALL missing_call_to_shutdown.cpp)
+target_link_libraries(${PROJECT_NAME}-missing_call_to_shutdown ${GTEST_LIBRARIES} ${catkin_LIBRARIES})
+
# Test node inspection functionality
add_executable(${PROJECT_NAME}-inspection EXCLUDE_FROM_ALL inspection.cpp)
target_link_libraries(${PROJECT_NAME}-inspection ${GTEST_LIBRARIES} ${catkin_LIBRARIES})
@@ -256,6 +262,8 @@ if(TARGET tests)
${PROJECT_NAME}-service_exception
${PROJECT_NAME}-service_call_repeatedly
${PROJECT_NAME}-multiple_init_fini
+ ${PROJECT_NAME}-missing_call_to_shutdown
+ ${PROJECT_NAME}-missing_call_to_shutdown_impl
${PROJECT_NAME}-inspection
${PROJECT_NAME}-service_adv_multiple
${PROJECT_NAME}-service_adv_a
@@ -324,6 +332,8 @@ add_dependencies(${PROJECT_NAME}-service_deadlock ${${PROJECT_NAME}_EXPORTED_TAR
add_dependencies(${PROJECT_NAME}-service_exception ${${PROJECT_NAME}_EXPORTED_TARGETS})
add_dependencies(${PROJECT_NAME}-service_call_repeatedly ${${PROJECT_NAME}_EXPORTED_TARGETS})
add_dependencies(${PROJECT_NAME}-multiple_init_fini ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-missing_call_to_shutdown ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-missing_call_to_shutdown_impl ${${PROJECT_NAME}_EXPORTED_TARGETS})
add_dependencies(${PROJECT_NAME}-inspection ${${PROJECT_NAME}_EXPORTED_TARGETS})
add_dependencies(${PROJECT_NAME}-service_adv_multiple ${${PROJECT_NAME}_EXPORTED_TARGETS})
add_dependencies(${PROJECT_NAME}-service_adv_a ${${PROJECT_NAME}_EXPORTED_TARGETS})
diff --git a/test/test_roscpp/test/src/missing_call_to_shutdown.cpp b/test/test_roscpp/test/src/missing_call_to_shutdown.cpp
new file mode 100644
index 0000000000..437ebc71f2
--- /dev/null
+++ b/test/test_roscpp/test/src/missing_call_to_shutdown.cpp
@@ -0,0 +1,52 @@
+/*
+ * Copyright (c) 2008, Willow Garage, Inc.
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *
+ * * Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * * Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in the
+ * documentation and/or other materials provided with the distribution.
+ * * Neither the name of Willow Garage, Inc. nor the names of its
+ * contributors may be used to endorse or promote products derived from
+ * this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+/* Author: David Gossow */
+
+#include
+#include
+
+TEST(roscpp, missingCallToShutdownInitOnly)
+{
+ int exit_code = system("rosrun test_roscpp test_roscpp-missing_call_to_shutdown_impl 0");
+ EXPECT_EQ(0, exit_code);
+}
+
+TEST(roscpp, missingCallToShutdownInitAndStart)
+{
+ int exit_code = system("rosrun test_roscpp test_roscpp-missing_call_to_shutdown_impl 1");
+ EXPECT_EQ(0, exit_code);
+}
+
+int
+main(int argc, char** argv)
+{
+ testing::InitGoogleTest(&argc, argv);
+ return RUN_ALL_TESTS();
+}
diff --git a/test/test_roscpp/test/src/missing_call_to_shutdown_impl.cpp b/test/test_roscpp/test/src/missing_call_to_shutdown_impl.cpp
new file mode 100644
index 0000000000..9b8d48691b
--- /dev/null
+++ b/test/test_roscpp/test/src/missing_call_to_shutdown_impl.cpp
@@ -0,0 +1,140 @@
+/*
+ * Copyright (c) 2008, Willow Garage, Inc.
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *
+ * * Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * * Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in the
+ * documentation and/or other materials provided with the distribution.
+ * * Neither the name of Willow Garage, Inc. nor the names of its
+ * contributors may be used to endorse or promote products derived from
+ * this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+/* Author: David Gossow */
+
+/*
+ * Call ros::start() explicitly, but never call ros::shutdown().
+ * ros::shutdown should be called automatically in this case.
+ */
+
+#include
+#include
+
+namespace ros
+{
+namespace console
+{
+extern bool g_shutting_down;
+}
+}
+
+namespace
+{
+
+enum TestId
+{
+ InitOnly = 0,
+ InitAndStart = 1
+};
+
+TestId test_id = InitOnly;
+
+void atexitCallback()
+{
+ bool hasError = false;
+
+ if (ros::ok())
+ {
+ std::cerr << "ERROR: ros::ok() returned true!" << std::endl;
+ hasError = true;
+ }
+ if (!ros::isShuttingDown())
+ {
+ std::cerr << "ERROR: ros::isShuttingDown() returned false!" << std::endl;
+ hasError = true;
+ }
+ if (ros::isStarted())
+ {
+ std::cerr << "ERROR: ros::isStarted() returned true!" << std::endl;
+ hasError = true;
+ }
+
+ if (!ros::isInitialized())
+ {
+ std::cerr << "ERROR: ros::isInitialized() returned false, although ros::init was called!" << std::endl;
+ std::cerr << "Due to legacy reasons, it should return true, even after ROS has been de-initialized." << std::endl;
+ hasError = true;
+ }
+
+ if (!ros::console::g_shutting_down)
+ {
+ std::cerr << "ERROR: ros::console::g_shutting_down returned false, but it should have been automatically shut down." << std::endl;
+ hasError = true;
+ }
+
+ if (hasError)
+ {
+ std::_Exit(1);
+ }
+}
+}
+
+int
+main(int argc, char** argv)
+{
+ if ( argc > 1 )
+ {
+ test_id = static_cast(atoi(argv[1]));
+ }
+
+ // Register atexit callbak which will be executed after ROS has been de-initialized.
+ if (atexit(atexitCallback) != 0)
+ {
+ std::cerr << "Failed to register atexit callback." << std::endl;
+ return 1;
+ }
+
+ switch (test_id)
+ {
+ case InitOnly:
+ // Test case 0: Call ros::init() explicitly, but never call ros::shutdown().
+ // ros::deInit should be called automatically in this case.
+ ros::init(argc, argv, "missing_call_to_shutdown" );
+ break;
+ case InitAndStart:
+ // Test case 1: Call ros::init() and ros::start() explicitly, but never call ros::shutdown().
+ // ros::shutdown should be called automatically in this case.
+ ros::init(argc, argv, "missing_call_to_shutdown" );
+ ros::start();
+ break;
+ default:
+ std::cerr << "Invalid test id: " << test_id << std::endl;
+ return 1;
+ break;
+ }
+
+ if (!ros::ok())
+ {
+ std::cerr << "Failed to start ROS." << std::endl;
+ return 1;
+ }
+
+ return 0;
+}
diff --git a/test/test_roscpp/test/src/multiple_init_fini.cpp b/test/test_roscpp/test/src/multiple_init_fini.cpp
index c8afa267f0..ac51264620 100644
--- a/test/test_roscpp/test/src/multiple_init_fini.cpp
+++ b/test/test_roscpp/test/src/multiple_init_fini.cpp
@@ -41,13 +41,18 @@
#include
#include "ros/ros.h"
+#include "ros/callback_queue.h"
+
#include
int g_argc;
char** g_argv;
+bool g_got_callback = false;
+
void callback(const test_roscpp::TestArrayConstPtr&)
{
+ g_got_callback = true;
}
TEST(roscpp, multipleInitAndFini)
@@ -60,15 +65,22 @@ TEST(roscpp, multipleInitAndFini)
for ( int i = 0; i < try_count; ++i )
{
+ g_got_callback = false;
+
ros::init( g_argc, g_argv, "multiple_init_fini" );
ros::NodeHandle nh;
ros::Subscriber sub = nh.subscribe("test", 1, callback);
ASSERT_TRUE(sub);
- ros::Publisher pub = nh.advertise( "test2", 1 );
+ ros::Publisher pub = nh.advertise( "test", 1 );
ASSERT_TRUE(pub);
+ pub.publish(test_roscpp::TestArray());
+ ros::getGlobalCallbackQueue()->callAvailable(ros::WallDuration(1));
+
+ ASSERT_TRUE(g_got_callback) << "did not receive a message in iteration " << i;
+
ros::shutdown();
}
}