[ros-nodelet-core] 01/03: New upstream version 1.9.8

Jochen Sprickerhof jspricke at moszumanska.debian.org
Thu Nov 17 18:10:25 UTC 2016


This is an automated email from the git hooks/post-receive script.

jspricke pushed a commit to annotated tag debian/1.9.8-1
in repository ros-nodelet-core.

commit f19ed6f5d319a31752fb7c5bb1fa427574101539
Author: Jochen Sprickerhof <git at jochen.sprickerhof.de>
Date:   Thu Nov 17 18:34:26 2016 +0100

    New upstream version 1.9.8
---
 nodelet/CHANGELOG.rst                              | 14 +++++
 nodelet/package.xml                                |  2 +-
 nodelet/src/loader.cpp                             | 18 +++++-
 nodelet/src/nodelet.cpp                            |  3 +-
 nodelet_core/CHANGELOG.rst                         |  3 +
 nodelet_core/package.xml                           |  2 +-
 nodelet_topic_tools/CHANGELOG.rst                  |  3 +
 nodelet_topic_tools/package.xml                    |  2 +-
 test_nodelet/CHANGELOG.rst                         | 14 +++++
 test_nodelet/CMakeLists.txt                        |  2 +
 test_nodelet/debug_logging.conf                    |  1 +
 test_nodelet/package.xml                           |  2 +-
 .../test/test_bond_break_on_shutdown.launch        |  4 ++
 test_nodelet/test/test_bond_break_on_shutdown.py   | 64 ++++++++++++++++++++++
 test_nodelet/test/test_unload_called_twice.launch  |  3 +
 test_nodelet/test/test_unload_called_twice.py      | 62 +++++++++++++++++++++
 test_nodelet_topic_tools/CHANGELOG.rst             |  3 +
 test_nodelet_topic_tools/package.xml               |  2 +-
 18 files changed, 195 insertions(+), 9 deletions(-)

diff --git a/nodelet/CHANGELOG.rst b/nodelet/CHANGELOG.rst
index a6ba0cb..c6eff85 100644
--- a/nodelet/CHANGELOG.rst
+++ b/nodelet/CHANGELOG.rst
@@ -2,6 +2,20 @@
 Changelog for package nodelet
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.9.8 (2016-11-15)
+------------------
+* Fix bond handling during nodelet unloading (`#51 <https://github.com/ros/nodelet_core/issues/51>`_)
+  * add test whether bond breaking on unload works (tests `#50 <https://github.com/ros/nodelet_core/issues/50>`_)
+  * disable callback for broken bond when we are breaking it
+  This avoids the nodelet::LoaderROS::unload() method to be called
+  twice for the same nodelet, causing an error output.
+  * use AsyncSpinner for nodelet load in order for the shutdown procedure to work
+  During shutdown, the bonds still need to communicate their status in order
+  for the nodelet to properly/cleanly/quickly unload. This requires the node
+  to spin.
+  * add test whether LoaderROS::unload() is called twice (tests `#50 <https://github.com/ros/nodelet_core/issues/50>`_)
+* Contributors: Daniel Seifert
+
 1.9.7 (2016-10-24)
 ------------------
 * Use rospkg instead of roslib in declared_nodelets
diff --git a/nodelet/package.xml b/nodelet/package.xml
index 7de17cf..95349b1 100644
--- a/nodelet/package.xml
+++ b/nodelet/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>nodelet</name>
-  <version>1.9.7</version>
+  <version>1.9.8</version>
   <description>
     The nodelet package is designed to provide a way to run multiple
     algorithms in the same process with zero copy transport between
diff --git a/nodelet/src/loader.cpp b/nodelet/src/loader.cpp
index 198b3c4..e57d534 100644
--- a/nodelet/src/loader.cpp
+++ b/nodelet/src/loader.cpp
@@ -89,6 +89,8 @@ private:
   bool serviceLoad(nodelet::NodeletLoad::Request &req,
                    nodelet::NodeletLoad::Response &res)
   {
+    boost::mutex::scoped_lock lock(lock_);
+
     // build map
     M_string remappings;
     if (req.remap_source_args.size() != req.remap_target_args.size())
@@ -127,6 +129,8 @@ private:
 
   bool unload(const std::string& name)
   {
+    boost::mutex::scoped_lock lock(lock_);
+
     bool success = parent_->unload(name);
     if (!success)
     {
@@ -134,8 +138,14 @@ private:
       return success;
     }
 
-    // Break the bond, if there is one
-    bond_map_.erase(name);
+    // break the bond, if there is one
+    M_stringToBond::iterator it = bond_map_.find(name);
+    if (it != bond_map_.end()) {
+        // disable callback for broken bond, as we are breaking it intentially now
+        it->second->setBrokenCallback(boost::function<void(void)>());
+        // erase (and break) bond
+        bond_map_.erase(name);
+    }
 
     return success;
   }
@@ -152,7 +162,9 @@ private:
   ros::ServiceServer load_server_;
   ros::ServiceServer unload_server_;
   ros::ServiceServer list_server_;
-  
+
+  boost::mutex lock_;
+
   ros::CallbackQueue bond_callback_queue_;
   ros::AsyncSpinner bond_spinner_;
   typedef boost::ptr_map<std::string, bond::Bond> M_stringToBond;
diff --git a/nodelet/src/nodelet.cpp b/nodelet/src/nodelet.cpp
index 6790024..b68184c 100644
--- a/nodelet/src/nodelet.cpp
+++ b/nodelet/src/nodelet.cpp
@@ -331,9 +331,10 @@ int
     if (arg_parser.isBondEnabled())
       bond.start();
     // Spin our own loop
+    ros::AsyncSpinner spinner(1);
+    spinner.start();
     while (!request_shutdown)
     {
-      ros::spinOnce();
       if (arg_parser.isBondEnabled() && bond.isBroken())
       {
         ROS_INFO("Bond broken, exiting");
diff --git a/nodelet_core/CHANGELOG.rst b/nodelet_core/CHANGELOG.rst
index b537bd9..9046cf5 100644
--- a/nodelet_core/CHANGELOG.rst
+++ b/nodelet_core/CHANGELOG.rst
@@ -2,6 +2,9 @@
 Changelog for package nodelet_core
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.9.8 (2016-11-15)
+------------------
+
 1.9.7 (2016-10-24)
 ------------------
 
diff --git a/nodelet_core/package.xml b/nodelet_core/package.xml
index e129603..a5a4218 100644
--- a/nodelet_core/package.xml
+++ b/nodelet_core/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>nodelet_core</name>
-  <version>1.9.7</version>
+  <version>1.9.8</version>
   <description>Nodelet Core Metapackage</description>
   <maintainer email="mikael at osrfoundation.org">Mikael Arguedas</maintainer>
   <license>BSD</license>
diff --git a/nodelet_topic_tools/CHANGELOG.rst b/nodelet_topic_tools/CHANGELOG.rst
index c8e35ec..9bcfef7 100644
--- a/nodelet_topic_tools/CHANGELOG.rst
+++ b/nodelet_topic_tools/CHANGELOG.rst
@@ -2,6 +2,9 @@
 Changelog for package nodelet_topic_tools
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.9.8 (2016-11-15)
+------------------
+
 1.9.7 (2016-10-24)
 ------------------
 
diff --git a/nodelet_topic_tools/package.xml b/nodelet_topic_tools/package.xml
index 9c29408..bec985d 100644
--- a/nodelet_topic_tools/package.xml
+++ b/nodelet_topic_tools/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>nodelet_topic_tools</name>
-  <version>1.9.7</version>
+  <version>1.9.8</version>
   <description>
     This package contains common nodelet tools such as a mux, demux and throttle.
   </description>
diff --git a/test_nodelet/CHANGELOG.rst b/test_nodelet/CHANGELOG.rst
index c37405c..31f42c6 100644
--- a/test_nodelet/CHANGELOG.rst
+++ b/test_nodelet/CHANGELOG.rst
@@ -2,6 +2,20 @@
 Changelog for package test_nodelet
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.9.8 (2016-11-15)
+------------------
+* Fix bond handling during nodelet unloading (`#51 <https://github.com/ros/nodelet_core/issues/51>`_)
+  * add test whether bond breaking on unload works (tests `#50 <https://github.com/ros/nodelet_core/issues/50>`_)
+  * disable callback for broken bond when we are breaking it
+  This avoids the nodelet::LoaderROS::unload() method to be called
+  twice for the same nodelet, causing an error output.
+  * use AsyncSpinner for nodelet load in order for the shutdown procedure to work
+  During shutdown, the bonds still need to communicate their status in order
+  for the nodelet to properly/cleanly/quickly unload. This requires the node
+  to spin.
+  * add test whether LoaderROS::unload() is called twice (tests `#50 <https://github.com/ros/nodelet_core/issues/50>`_)
+* Contributors: Daniel Seifert
+
 1.9.7 (2016-10-24)
 ------------------
 
diff --git a/test_nodelet/CMakeLists.txt b/test_nodelet/CMakeLists.txt
index 0daf84d..eaaa088 100644
--- a/test_nodelet/CMakeLists.txt
+++ b/test_nodelet/CMakeLists.txt
@@ -29,6 +29,8 @@ if(CATKIN_ENABLE_TESTING)
   add_dependencies(tests test_console)
 
   add_rostest(test/test_console.launch)
+  add_rostest(test/test_bond_break_on_shutdown.launch)
+  add_rostest(test/test_unload_called_twice.launch)
 
   # Not a real test. Tries to measure overhead of CallbackQueueManager.
   add_executable(benchmark src/benchmark.cpp)
diff --git a/test_nodelet/debug_logging.conf b/test_nodelet/debug_logging.conf
new file mode 100644
index 0000000..9cd2f9d
--- /dev/null
+++ b/test_nodelet/debug_logging.conf
@@ -0,0 +1 @@
+log4j.logger.ros=DEBUG
diff --git a/test_nodelet/package.xml b/test_nodelet/package.xml
index 02752f3..bd419e5 100644
--- a/test_nodelet/package.xml
+++ b/test_nodelet/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>test_nodelet</name>
-  <version>1.9.7</version>
+  <version>1.9.8</version>
   <description>
     A package for nodelet unit tests
   </description>
diff --git a/test_nodelet/test/test_bond_break_on_shutdown.launch b/test_nodelet/test/test_bond_break_on_shutdown.launch
new file mode 100644
index 0000000..9a20907
--- /dev/null
+++ b/test_nodelet/test/test_bond_break_on_shutdown.launch
@@ -0,0 +1,4 @@
+<launch>
+  <env name="ROSCONSOLE_CONFIG_FILE" value="$(find test_nodelet)/debug_logging.conf"/>
+  <test test-name="test_bond_break_on_shutdown" pkg="test_nodelet" type="test_bond_break_on_shutdown.py" />
+</launch>
diff --git a/test_nodelet/test/test_bond_break_on_shutdown.py b/test_nodelet/test/test_bond_break_on_shutdown.py
new file mode 100755
index 0000000..83335a5
--- /dev/null
+++ b/test_nodelet/test/test_bond_break_on_shutdown.py
@@ -0,0 +1,64 @@
+#!/usr/bin/env python
+
+import roslib; roslib.load_manifest('test_nodelet')
+import rospy
+import unittest
+import rostest
+import signal
+import subprocess
+import time
+
+from nodelet.srv import *
+
+class TestBondBreakOnShutdown(unittest.TestCase):
+    def test_bond_break_on_shutdown(self):
+        '''
+        Test that the bond is broken cleanly when closing a nodelet loader (#50).
+        This relies on a debug message printed by the bondcpp package in case
+        of error.
+        '''
+
+        # start nodelet manager
+        proc_manager = subprocess.Popen(["rosrun", "nodelet", "nodelet", "manager", "__name:=nodelet_manager"],
+            stdout=subprocess.PIPE,
+            stderr=subprocess.PIPE,
+            bufsize=-1
+        )
+
+        # wait for nodelet manager to be ready
+        try:
+            rospy.wait_for_service('/nodelet_manager/load_nodelet', timeout=2)
+        except:
+            self.fail("Could not determine that nodelet manager has started")
+
+        # load a nodelet
+        proc_nodelet = subprocess.Popen(["rosrun", "nodelet", "nodelet", "load", "test_nodelet/Plus", "nodelet_manager", "__name:=test"],
+            stdout=subprocess.PIPE,
+            stderr=subprocess.PIPE,
+            bufsize=-1
+        )
+
+        # wait for it to be ready
+        try:
+            rospy.wait_for_service('test/get_loggers', timeout=2)
+        except:
+            self.fail("Could not determine that nodelet has started")
+        time.sleep(1)
+
+        # stop the nodelet loader via signal (similar to roslaunch killing it)
+        proc_nodelet.send_signal(signal.SIGINT)
+        (n_out, n_err) = proc_nodelet.communicate()
+
+        # stop the nodelet manager, too
+        proc_manager.send_signal(signal.SIGINT)
+        (m_out, m_err) = proc_manager.communicate()
+
+        # check that nodelet unloaded and there was no error with bond breaking
+        self.assertIn('Unloading nodelet /test from manager nodelet_manager', n_out)
+        self.assertNotIn('Bond failed to break on destruction', m_out)
+        self.assertNotIn('Bond failed to break on destruction', n_out)
+
+if __name__ == '__main__':
+    rospy.init_node('test_bond_break_on_shutdown')
+    rostest.unitrun('test_bond_break_on_shutdown', 'test_bond_break_on_shutdown', TestBondBreakOnShutdown)
+
diff --git a/test_nodelet/test/test_unload_called_twice.launch b/test_nodelet/test/test_unload_called_twice.launch
new file mode 100644
index 0000000..f4267fb
--- /dev/null
+++ b/test_nodelet/test/test_unload_called_twice.launch
@@ -0,0 +1,3 @@
+<launch>
+  <test test-name="unload_called_twice" pkg="test_nodelet" type="test_unload_called_twice.py" />
+</launch>
diff --git a/test_nodelet/test/test_unload_called_twice.py b/test_nodelet/test/test_unload_called_twice.py
new file mode 100755
index 0000000..d001f52
--- /dev/null
+++ b/test_nodelet/test/test_unload_called_twice.py
@@ -0,0 +1,62 @@
+#!/usr/bin/env python
+
+import roslib; roslib.load_manifest('test_nodelet')
+import rospy
+import unittest
+import rostest
+import signal
+import subprocess
+import time
+
+from nodelet.srv import *
+
+class TestUnloadCalledTwice(unittest.TestCase):
+    def test_unload_called_twice(self):
+        '''
+        Test that when a nodelet loader is stopped and requests unloading,
+        the unload() call in LoaderROS is not run twice (#50).
+        '''
+
+        # start nodelet manager
+        proc_manager = subprocess.Popen(["rosrun", "nodelet", "nodelet", "manager", "__name:=nodelet_manager"],
+            stdout=subprocess.PIPE,
+            stderr=subprocess.PIPE,
+            bufsize=-1
+        )
+
+        # wait for nodelet manager to be ready
+        try:
+            rospy.wait_for_service('/nodelet_manager/load_nodelet', timeout=2)
+        except:
+            self.fail("Could not determine that nodelet manager has started")
+
+        # load nodelet
+        proc_nodelet = subprocess.Popen(["rosrun", "nodelet", "nodelet", "load", "test_nodelet/Plus", "nodelet_manager", "__name:=test"],
+            stdout=subprocess.PIPE,
+            stderr=subprocess.PIPE
+        )
+
+        # wait for nodelet to be ready
+        try:
+            rospy.wait_for_service('test/get_loggers', timeout=2)
+        except:
+            self.fail("Could not determine that nodelet has started")
+        time.sleep(1)
+
+        # stop the nodelet loader via signal (similar to roslaunch killing it)
+        proc_nodelet.send_signal(signal.SIGINT)
+        (n_out, n_err) = proc_nodelet.communicate()
+
+        # stop the nodelet manager, too
+        proc_manager.send_signal(signal.SIGINT)
+        (m_out, m_err) = proc_manager.communicate()
+
+        # check that nodelet unloaded and that LoaderROS::unload() does not
+        # complain about nodelet not being found (an indication that it was called
+        # again after the nodelet was already unloaded)
+        self.assertIn('Unloading nodelet /test from manager nodelet_manager', n_out)
+        self.assertNotIn('Failed to find nodelet with name', m_err)
+
+if __name__ == '__main__':
+    rospy.init_node('test_unload_called_twice')
+    rostest.unitrun('test_unload_called_twice', 'test_unload_called_twice', TestUnloadCalledTwice)
diff --git a/test_nodelet_topic_tools/CHANGELOG.rst b/test_nodelet_topic_tools/CHANGELOG.rst
index 6f61b87..c25d07b 100644
--- a/test_nodelet_topic_tools/CHANGELOG.rst
+++ b/test_nodelet_topic_tools/CHANGELOG.rst
@@ -2,6 +2,9 @@
 Changelog for package test_nodelet_topic_tools
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.9.8 (2016-11-15)
+------------------
+
 1.9.7 (2016-10-24)
 ------------------
 
diff --git a/test_nodelet_topic_tools/package.xml b/test_nodelet_topic_tools/package.xml
index 3f9aea1..3b96644 100644
--- a/test_nodelet_topic_tools/package.xml
+++ b/test_nodelet_topic_tools/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>test_nodelet_topic_tools</name>
-  <version>1.9.7</version>
+  <version>1.9.8</version>
   <description>
     A package for nodelet_topic_tools unit tests.
   </description>

-- 
Alioth's /usr/local/bin/git-commit-notice on /srv/git.debian.org/git/debian-science/packages/ros/ros-nodelet-core.git



More information about the debian-science-commits mailing list