diff -Nru ros-nodelet-core-1.9.8/debian/changelog ros-nodelet-core-1.9.16/debian/changelog --- ros-nodelet-core-1.9.8/debian/changelog 2018-08-08 10:20:05.000000000 +0000 +++ ros-nodelet-core-1.9.16/debian/changelog 2018-11-03 12:49:15.000000000 +0000 @@ -1,14 +1,15 @@ -ros-nodelet-core (1.9.8-2build2) cosmic; urgency=medium +ros-nodelet-core (1.9.16-1) unstable; urgency=medium - * Rebuild against new libtinyxml2-6a. + * New upstream version 1.9.16 + * Update copyright + * Rebase patch + * Bump policy version (no changes) + * simplify d/rules + * Fix lintian warning + * Bump Soname due to ABI change + * Add Python 3 package - -- Gianfranco Costamagna Wed, 08 Aug 2018 12:20:05 +0200 - -ros-nodelet-core (1.9.8-2build1) cosmic; urgency=medium - - * Rebuild against new libtinyxml2-6a. - - -- Gianfranco Costamagna Wed, 08 Aug 2018 12:03:18 +0200 + -- Jochen Sprickerhof Sat, 03 Nov 2018 13:49:15 +0100 ros-nodelet-core (1.9.8-2) unstable; urgency=medium diff -Nru ros-nodelet-core-1.9.8/debian/control ros-nodelet-core-1.9.16/debian/control --- ros-nodelet-core-1.9.8/debian/control 2018-07-31 20:17:56.000000000 +0000 +++ ros-nodelet-core-1.9.16/debian/control 2018-11-03 12:47:01.000000000 +0000 @@ -12,8 +12,9 @@ libclass-loader-dev, libroslib-dev, libdynamic-reconfigure-config-init-mutex-dev, libboost-thread-dev, libboost-dev, dh-python, python-dev, uuid-dev, python-nose, libroscpp-msg-dev, - python-dynamic-reconfigure, python-roslib -Standards-Version: 4.1.5 + python-dynamic-reconfigure, python-roslib, python3-dev, + python3-nose, python3-dynamic-reconfigure, python3-roslib, +Standards-Version: 4.2.1 Section: libs Rules-Requires-Root: no Homepage: https://wiki.ros.org/nodelet_core @@ -38,14 +39,27 @@ Section: python Architecture: all Depends: ${python:Depends}, ${shlibs:Depends}, ${misc:Depends} -Description: Robot OS nodelet library - service files - Python +Description: Robot OS nodelet library - service files - Python 2 This package is part of Robot OS (ROS). Nodelet is designed to provide a way to run multiple algorithms in the same process with zero copy transport between algorithms. The nodelet base class needed for implementing a nodelet, and the NodeletLoader class used for instantiating nodelets are provided. . - This package contains the Python interface. + This package contains the Python 2 interface. + +Package: python3-nodelet +Section: python +Architecture: all +Depends: ${python3:Depends}, ${shlibs:Depends}, ${misc:Depends} +Description: Robot OS nodelet library - service files - Python 3 + This package is part of Robot OS (ROS). Nodelet is designed to + provide a way to run multiple algorithms in the same process with + zero copy transport between algorithms. The nodelet base class needed + for implementing a nodelet, and the NodeletLoader class used for + instantiating nodelets are provided. + . + This package contains the Python 3 interface. Package: cl-nodelet Section: lisp @@ -64,7 +78,7 @@ Package: libnodeletlib-dev Section: libdevel Architecture: any -Depends: libnodeletlib0d (= ${binary:Version}), ${misc:Depends}, ${shlibs:Depends}, libbondcpp-dev, ros-message-runtime, pluginlib-dev, librosconsole-dev, libroscpp-dev, libstd-msgs-dev, libnodelet-dev +Depends: libnodeletlib1d (= ${binary:Version}), ${misc:Depends}, ${shlibs:Depends}, libbondcpp-dev, ros-message-runtime, pluginlib-dev, librosconsole-dev, libroscpp-dev, libstd-msgs-dev, libnodelet-dev Description: Robot OS nodelet library - development This package is part of Robot OS (ROS). Nodelet is designed to provide a way to run multiple algorithms in the same process with @@ -74,7 +88,7 @@ . This package contains the development files for the library. -Package: libnodeletlib0d +Package: libnodeletlib1d Architecture: any Depends: ${shlibs:Depends}, ${misc:Depends} Multi-Arch: same @@ -89,7 +103,7 @@ Package: libnodeletlib-tools Architecture: any -Depends: ${shlibs:Depends}, ${misc:Depends} +Depends: ${shlibs:Depends}, ${misc:Depends}, python Multi-Arch: foreign Description: Robot OS nodelet library This package is part of Robot OS (ROS). Nodelet is designed to @@ -116,10 +130,22 @@ Section: python Architecture: all Depends: ${python:Depends}, ${shlibs:Depends}, ${misc:Depends} -Description: Robot OS nodelet_topic_tools library - service files +Description: Robot OS nodelet_topic_tools library - Python 2 service files + This package is part of Robot OS (ROS). Nodelet is designed to + provide a way to run multiple algorithms in the same process with + zero copy transport between algorithms. + . + This package contains the generated Python 2 package for common + nodelet tools such as a mux, demux and throttle. + +Package: python3-nodelet-topic-tools +Section: python +Architecture: all +Depends: ${python3:Depends}, ${shlibs:Depends}, ${misc:Depends} +Description: Robot OS nodelet_topic_tools library - Python 3 service files This package is part of Robot OS (ROS). Nodelet is designed to provide a way to run multiple algorithms in the same process with zero copy transport between algorithms. . - This package contains the generated Python package for common + This package contains the generated Python 3 package for common nodelet tools such as a mux, demux and throttle. diff -Nru ros-nodelet-core-1.9.8/debian/copyright ros-nodelet-core-1.9.16/debian/copyright --- ros-nodelet-core-1.9.8/debian/copyright 2018-07-31 20:17:12.000000000 +0000 +++ ros-nodelet-core-1.9.16/debian/copyright 2018-11-03 12:28:00.000000000 +0000 @@ -4,18 +4,11 @@ Source: https://github.com/ros/nodelet_core Files: * -Copyright: 2009-2011 Willow Garage, Inc. +Copyright: 2008-2011, Willow Garage, Inc + 2014, Open Source Robotics Foundation, Inc + 2014-2016, JSK Lab, University of Tokyo + 2016, University of Patras License: BSD-3-clause -# Authors from package.xml Radu Bogdan Rusu -# and Tully Foote - -Files: include/nodelet/exception.h -Copyright: 2010, Willow Garage, Inc. -License: BSD-3-clause-Stanford-Willow - -Files: test_nodelet/src/failing_nodelet.cpp -Copyright: 2014, Open Source Robotics Foundation, Inc -License: BSD-3-clause-OSRF Files: debian/* Copyright: 2015, Thomas Moulard , @@ -34,70 +27,12 @@ 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 + * Neither the name of copyright holder 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. - -License: BSD-3-clause-Stanford-Willow - 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 Stanford University or 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. - -License: BSD-3-clause-OSRF - 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 Open Source Robotics Foundation, 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, diff -Nru ros-nodelet-core-1.9.8/debian/libnodeletlib0d.install ros-nodelet-core-1.9.16/debian/libnodeletlib0d.install --- ros-nodelet-core-1.9.8/debian/libnodeletlib0d.install 2016-07-10 21:15:42.000000000 +0000 +++ ros-nodelet-core-1.9.16/debian/libnodeletlib0d.install 1970-01-01 00:00:00.000000000 +0000 @@ -1 +0,0 @@ -usr/lib/*/lib*.so.* diff -Nru ros-nodelet-core-1.9.8/debian/libnodeletlib1d.install ros-nodelet-core-1.9.16/debian/libnodeletlib1d.install --- ros-nodelet-core-1.9.8/debian/libnodeletlib1d.install 1970-01-01 00:00:00.000000000 +0000 +++ ros-nodelet-core-1.9.16/debian/libnodeletlib1d.install 2018-07-31 20:29:40.000000000 +0000 @@ -0,0 +1 @@ +usr/lib/*/lib*.so.* diff -Nru ros-nodelet-core-1.9.8/debian/patches/0002-Add-Debian-specific-SOVERSION.patch ros-nodelet-core-1.9.16/debian/patches/0002-Add-Debian-specific-SOVERSION.patch --- ros-nodelet-core-1.9.8/debian/patches/0002-Add-Debian-specific-SOVERSION.patch 2017-06-23 17:04:25.000000000 +0000 +++ ros-nodelet-core-1.9.16/debian/patches/0002-Add-Debian-specific-SOVERSION.patch 2018-11-03 12:42:53.000000000 +0000 @@ -7,14 +7,14 @@ 1 file changed, 1 insertion(+) diff --git a/nodelet/CMakeLists.txt b/nodelet/CMakeLists.txt -index 5d9eea4..2773adf 100644 +index 37db68c..60ceab3 100644 --- a/nodelet/CMakeLists.txt +++ b/nodelet/CMakeLists.txt -@@ -31,6 +31,7 @@ include_directories(include ${catkin_INCLUDE_DIRS} ${BOOST_INCLUDE_DIRS}) +@@ -43,6 +43,7 @@ include_directories( add_library(nodeletlib src/nodelet_class.cpp src/loader.cpp src/callback_queue.cpp src/callback_queue_manager.cpp) target_link_libraries(nodeletlib ${catkin_LIBRARIES} ${BOOST_LIBRARIES}) add_dependencies(nodeletlib ${nodelet_EXPORTED_TARGETS}) -+set_target_properties(nodeletlib PROPERTIES VERSION ${nodelet_VERSION} SOVERSION "0d") ++set_target_properties(nodeletlib PROPERTIES VERSION ${nodelet_VERSION} SOVERSION "1d") add_executable(nodelet src/nodelet.cpp) target_link_libraries(nodelet nodeletlib ${UUID_LIBRARIES} ${catkin_LIBRARIES} ${BOOST_LIBRARIES}) diff -Nru ros-nodelet-core-1.9.8/debian/python3-nodelet.pyinstall ros-nodelet-core-1.9.16/debian/python3-nodelet.pyinstall --- ros-nodelet-core-1.9.8/debian/python3-nodelet.pyinstall 1970-01-01 00:00:00.000000000 +0000 +++ ros-nodelet-core-1.9.16/debian/python3-nodelet.pyinstall 2018-11-03 12:47:35.000000000 +0000 @@ -0,0 +1,2 @@ +debian/tmp/usr/lib/python2*/*/nodelet/*.py nodelet +debian/tmp/usr/lib/python2*/*/nodelet/srv/*.py nodelet.srv diff -Nru ros-nodelet-core-1.9.8/debian/python3-nodelet-topic-tools.pyinstall ros-nodelet-core-1.9.16/debian/python3-nodelet-topic-tools.pyinstall --- ros-nodelet-core-1.9.8/debian/python3-nodelet-topic-tools.pyinstall 1970-01-01 00:00:00.000000000 +0000 +++ ros-nodelet-core-1.9.16/debian/python3-nodelet-topic-tools.pyinstall 2018-11-03 12:48:02.000000000 +0000 @@ -0,0 +1,2 @@ +debian/tmp/usr/lib/python2*/*/nodelet_topic_tools/*.py nodelet_topic_tools +debian/tmp/usr/lib/python2*/*/nodelet_topic_tools/cfg/*.py nodelet_topic_tools.cfg diff -Nru ros-nodelet-core-1.9.8/debian/rules ros-nodelet-core-1.9.16/debian/rules --- ros-nodelet-core-1.9.8/debian/rules 2018-07-31 20:18:06.000000000 +0000 +++ ros-nodelet-core-1.9.16/debian/rules 2018-11-03 12:47:23.000000000 +0000 @@ -1,6 +1,4 @@ #!/usr/bin/make -f -DPKG_EXPORT_BUILDFLAGS = 1 -include /usr/share/dpkg/default.mk %: - dh $@ --with=python2 --buildsystem=cmake + dh $@ --with=python2,python3 --buildsystem=cmake diff -Nru ros-nodelet-core-1.9.8/nodelet/CHANGELOG.rst ros-nodelet-core-1.9.16/nodelet/CHANGELOG.rst --- ros-nodelet-core-1.9.8/nodelet/CHANGELOG.rst 2016-11-15 15:32:47.000000000 +0000 +++ ros-nodelet-core-1.9.16/nodelet/CHANGELOG.rst 2018-11-03 12:16:03.000000000 +0000 @@ -2,6 +2,59 @@ Changelog for package nodelet ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.9.16 (2018-04-27) +------------------- +* uuid dependency fixup (`#74 `_) + * don't export uuid library + * wrap for readability +* Contributors: Mikael Arguedas + +1.9.15 (2018-03-16) +------------------- +* use new pluginlib headers (`#73 `_) +* Contributors: Mikael Arguedas + +1.9.14 (2017-11-15) +------------------- +* declared_nodelets: continue on missing plugin xml (`#70 `_) +* Contributors: Furushchev + +1.9.13 (2017-10-27) +------------------- +* Drop unneeded forward declaration. (`#68 `_) +* Contributors: Mike Purvis + +1.9.12 (2017-08-04) +------------------- + +1.9.11 (2017-07-27) +------------------- +* Add getRemappingArgs method to nodelet to reuse it in subclass (`#61 `_) +* remove trailing whitespaces (`#62 `_) +* switch to package format 2 (`#63 `_) +* Show pkg and manifest file with verbose option (`#59 `_) +* Contributors: Kentaro Wada, Mikael Arguedas + +1.9.10 (2017-03-27) +------------------- +* installs the list_nodelets script (`#58 `_) + * python3 compatibility + * pep8 + * install list_nodelets + * print message with service name +* return outside of try catch +* fix unused var warning +* give node a name, empty node names not supported since https://github.com/ros/ros_comm/commit/bd3af70520648783da8aa4d3610f234a4d2bd41f +* remove tabs +* fix help message +* Contributors: Mikael Arguedas + +1.9.9 (2017-02-17) +------------------ +* drop unused dependency on tinyxml (`#54 `_) +* Install the declared_nodelets script (`#53 `_) +* Contributors: Dmitry Rozhkov, Kentaro Wada + 1.9.8 (2016-11-15) ------------------ * Fix bond handling during nodelet unloading (`#51 `_) diff -Nru ros-nodelet-core-1.9.8/nodelet/CMakeLists.txt ros-nodelet-core-1.9.16/nodelet/CMakeLists.txt --- ros-nodelet-core-1.9.8/nodelet/CMakeLists.txt 2016-11-15 15:32:47.000000000 +0000 +++ ros-nodelet-core-1.9.16/nodelet/CMakeLists.txt 2018-11-03 12:16:03.000000000 +0000 @@ -2,7 +2,15 @@ project(nodelet) ## Find catkin dependencies -find_package(catkin REQUIRED bondcpp cmake_modules message_generation pluginlib rosconsole roscpp std_msgs) +find_package(catkin REQUIRED + bondcpp + cmake_modules + message_generation + pluginlib + rosconsole + roscpp + std_msgs +) ## Find Boost (only headers) find_package(Boost REQUIRED) @@ -17,13 +25,17 @@ generate_messages(DEPENDENCIES std_msgs) catkin_package( - INCLUDE_DIRS include ${UUID_INCLUDE_DIRS} - LIBRARIES nodeletlib ${UUID_LIBRARIES} + INCLUDE_DIRS include + LIBRARIES nodeletlib CATKIN_DEPENDS bondcpp message_runtime pluginlib rosconsole roscpp std_msgs DEPENDS Boost ) -include_directories(include ${catkin_INCLUDE_DIRS} ${BOOST_INCLUDE_DIRS}) +include_directories( + include + ${catkin_INCLUDE_DIRS} + ${BOOST_INCLUDE_DIRS} + ${UUID_INCLUDE_DIRS}) # Debug only, collects stats on how callbacks are doled out to worker threads #add_definitions(-DNODELET_QUEUE_DEBUG) @@ -36,6 +48,8 @@ target_link_libraries(nodelet nodeletlib ${UUID_LIBRARIES} ${catkin_LIBRARIES} ${BOOST_LIBRARIES}) # install +catkin_install_python(PROGRAMS scripts/declared_nodelets scripts/list_nodelets + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) install(DIRECTORY include/${PROJECT_NAME}/ DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} ) diff -Nru ros-nodelet-core-1.9.8/nodelet/include/nodelet/detail/callback_queue_manager.h ros-nodelet-core-1.9.16/nodelet/include/nodelet/detail/callback_queue_manager.h --- ros-nodelet-core-1.9.8/nodelet/include/nodelet/detail/callback_queue_manager.h 2016-11-15 15:32:47.000000000 +0000 +++ ros-nodelet-core-1.9.16/nodelet/include/nodelet/detail/callback_queue_manager.h 2018-11-03 12:16:03.000000000 +0000 @@ -84,7 +84,6 @@ struct ThreadInfo; void workerThread(ThreadInfo*); - class ThreadInfo; ThreadInfo* getSmallestQueue(); struct QueueInfo @@ -135,7 +134,7 @@ Record(double stamp, uint32_t tasks, bool threaded) : stamp(stamp), tasks(tasks), threaded(threaded) {} - + double stamp; uint32_t tasks; bool threaded; diff -Nru ros-nodelet-core-1.9.8/nodelet/include/nodelet/loader.h ros-nodelet-core-1.9.16/nodelet/include/nodelet/loader.h --- ros-nodelet-core-1.9.8/nodelet/include/nodelet/loader.h 2016-11-15 15:32:47.000000000 +0000 +++ ros-nodelet-core-1.9.16/nodelet/include/nodelet/loader.h 2018-11-03 12:16:03.000000000 +0000 @@ -69,7 +69,7 @@ * create nodelet instances */ Loader(const boost::function (const std::string& lookup_name)>& create_instance); - + ~Loader(); /** \brief Load a nodelet */ @@ -84,7 +84,7 @@ /**\brief List the names of all loaded nodelets */ std::vector listLoadedNodelets(); - + private: boost::mutex lock_; /// + + + nodelet - 1.9.8 + 1.9.16 The nodelet package is designed to provide a way to run multiple algorithms in the same process with zero copy transport between @@ -21,25 +23,17 @@ catkin - bondcpp - boost cmake_modules message_generation - pluginlib - rosconsole - roscpp - rospy - std_msgs - tinyxml - uuid - - bondcpp - boost - message_runtime - pluginlib - rosconsole - roscpp - std_msgs - tinyxml - uuid + + bondcpp + boost + pluginlib + rosconsole + roscpp + std_msgs + uuid + + message_runtime + rospy diff -Nru ros-nodelet-core-1.9.8/nodelet/scripts/declared_nodelets ros-nodelet-core-1.9.16/nodelet/scripts/declared_nodelets --- ros-nodelet-core-1.9.8/nodelet/scripts/declared_nodelets 2016-11-15 15:32:47.000000000 +0000 +++ ros-nodelet-core-1.9.16/nodelet/scripts/declared_nodelets 2018-11-03 12:16:03.000000000 +0000 @@ -32,40 +32,71 @@ # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. +from __future__ import print_function +import argparse +import os +import sys +import xml +from xml.dom import minidom import rospkg -from xml.dom import minidom -import xml -nodelet_files = [] -rp = rospkg.RosPack() -for p in rp.get_depends_on('nodelet', implicit=False): - #print "Processing package %s to find declared nodelets"%p - manifest = rp.get_manifest(p) - for e in manifest.exports: - try: - if e.__dict__['tag'] == 'nodelet': - plugin_file = e.get('plugin') - if plugin_file: - plugin_file = plugin_file.replace('${prefix}', rp.get_path(p)) - nodelet_files.append(plugin_file) - except Exception, ex: - print ex - -declared_nodelets = [] - -for f in nodelet_files: - with open(f) as fh: - try: - dom = minidom.parse(fh) - for lib in dom.getElementsByTagName('library'): - for name in lib.getElementsByTagName('class'): - declared_nodelets.append(name.getAttribute('name')) - except xml.parsers.expat.ExpatError, ex: - "failed to parse file %s"%f - -#print "\n\nDECLARED NODELETS\n=================" -for n in declared_nodelets: - print n +def main(): + parser = argparse.ArgumentParser() + parser.add_argument('-v', '--verbose', action='store_true') + parser.add_argument('-p', '--package') + args = parser.parse_args() + + rp = rospkg.RosPack() + nodelet_files = [] + for p in rp.get_depends_on('nodelet', implicit=False): + manifest = rp.get_manifest(p) + for e in manifest.exports: + try: + if e.__dict__['tag'] == 'nodelet': + plugin_file = e.get('plugin') + if plugin_file: + plugin_file = plugin_file.replace('${prefix}', rp.get_path(p)) + nodelet_files.append((p, plugin_file)) + except Exception as e: + print(e, file=sys.stderr) + + declared_nodelets = [] + for p, f in nodelet_files: + nodelets = [] + if not os.path.isfile(f): + print('%s: %s' % (f, 'The file does not exist.'), file=sys.stderr) + continue + with open(f) as fh: + try: + dom = minidom.parse(fh) + for lib in dom.getElementsByTagName('library'): + for name in lib.getElementsByTagName('class'): + nodelets.append(name.getAttribute('name')) + except xml.parsers.expat.ExpatError as e: + print('%s: %s' % (f, e), file=sys.stderr) + continue + declared_nodelets.append({ + 'package': p, + 'manifest': f, + 'nodelets': nodelets, + }) + + for declared in declared_nodelets: + if args.package and declared['package'] != args.package: + continue + if args.verbose: + print('- package: %s' % declared['package']) + print(' manifest: %s' % declared['manifest']) + print(' nodelets:') + for nodelet in declared['nodelets']: + print(' - %s' % nodelet) + else: + for nodelet in declared['nodelets']: + print(nodelet) + + +if __name__ == '__main__': + main() diff -Nru ros-nodelet-core-1.9.8/nodelet/scripts/list_nodelets ros-nodelet-core-1.9.16/nodelet/scripts/list_nodelets --- ros-nodelet-core-1.9.8/nodelet/scripts/list_nodelets 2016-11-15 15:32:47.000000000 +0000 +++ ros-nodelet-core-1.9.16/nodelet/scripts/list_nodelets 2018-11-03 12:16:03.000000000 +0000 @@ -1,42 +1,43 @@ #! /usr/bin/env python # Provides quick access to the services exposed by MechanismControlNode +from __future__ import print_function import roslib roslib.load_manifest('nodelet') from optparse import OptionParser -import rospy, sys +import rospy from nodelet.srv import NodeletList + class NodeletInterface(): def list_nodelets(self, manager): - service_manager = manager+"/list" + service_manager = manager + "/list" + rospy.loginfo('Waiting for service: %s', service_manager) rospy.wait_for_service(service_manager) service_client = rospy.ServiceProxy(service_manager, NodeletList) resp = service_client() - print resp - + print(resp) def usage(): return '''list_nodelets - List active nodelets on the manager''' + if __name__ == '__main__': parser = OptionParser(usage=usage()) - rospy.init_node("nodelet", anonymous=True) options, args = parser.parse_args(rospy.myargv()) - - if len(args) != 2: - parser.error("Command 'list_nodelets' requires 2 arguments not %d"%len(args)) + parser.error("Command 'list_nodelets' requires 2 arguments not %d" % len(args)) manager = args[1] - service_manager = manager+"/list" + service_manager = manager + "/list" + rospy.loginfo('Waiting for service: %s', service_manager) rospy.wait_for_service(service_manager) service_client = rospy.ServiceProxy(service_manager, NodeletList) resp = service_client() - print resp + print(resp) diff -Nru ros-nodelet-core-1.9.8/nodelet/src/callback_queue.cpp ros-nodelet-core-1.9.16/nodelet/src/callback_queue.cpp --- ros-nodelet-core-1.9.8/nodelet/src/callback_queue.cpp 2016-11-15 15:32:47.000000000 +0000 +++ ros-nodelet-core-1.9.16/nodelet/src/callback_queue.cpp 2018-11-03 12:16:03.000000000 +0000 @@ -74,7 +74,7 @@ if (!tracker) return ros::CallbackQueue::Disabled; } - + return queue_.callOne(); } diff -Nru ros-nodelet-core-1.9.8/nodelet/src/callback_queue_manager.cpp ros-nodelet-core-1.9.16/nodelet/src/callback_queue_manager.cpp --- ros-nodelet-core-1.9.8/nodelet/src/callback_queue_manager.cpp 2016-11-15 15:32:47.000000000 +0000 +++ ros-nodelet-core-1.9.16/nodelet/src/callback_queue_manager.cpp 2018-11-03 12:16:03.000000000 +0000 @@ -49,7 +49,7 @@ { if (num_worker_threads_ == 0) num_worker_threads_ = boost::thread::hardware_concurrency(); - + tg_.create_thread(boost::bind(&CallbackQueueManager::managerThread, this)); size_t num_threads = getNumWorkerThreads(); @@ -63,7 +63,7 @@ CallbackQueueManager::~CallbackQueueManager() { stop(); - + #ifdef NODELET_QUEUE_DEBUG // Write out task assignment histories for each thread typedef ThreadInfo::Record Record; diff -Nru ros-nodelet-core-1.9.8/nodelet/src/loader.cpp ros-nodelet-core-1.9.16/nodelet/src/loader.cpp --- ros-nodelet-core-1.9.8/nodelet/src/loader.cpp 2016-11-15 15:32:47.000000000 +0000 +++ ros-nodelet-core-1.9.16/nodelet/src/loader.cpp 2018-11-03 12:16:03.000000000 +0000 @@ -31,7 +31,7 @@ #include #include #include -#include +#include #include #include @@ -52,7 +52,7 @@ Loader ensures that the CallbackQueues associated with a Nodelet outlive that Nodelet. CallbackQueueManager ensures that CallbackQueues continue to survive as -long as they have pending callbacks. +long as they have pending callbacks. CallbackQueue holds a weak_ptr to its associated Nodelet, which it attempts to lock before invoking any callback. So any lingering callbacks processed after a @@ -150,7 +150,7 @@ return success; } - bool serviceList(nodelet::NodeletList::Request &req, + bool serviceList(nodelet::NodeletList::Request &, nodelet::NodeletList::Response &res) { res.nodelets = parent_->listLoadedNodelets(); @@ -231,7 +231,7 @@ server_nh.param("num_worker_threads", num_threads_param, 0); callback_manager_.reset(new detail::CallbackQueueManager(num_threads_param)); ROS_INFO("Initializing nodelet with %d worker threads.", (int)callback_manager_->getNumWorkerThreads()); - + services_.reset(new LoaderROS(parent, server_nh)); } }; @@ -316,7 +316,6 @@ /// @todo Can we delay processing the queues until Nodelet::onInit() returns? ROS_DEBUG("Done initing nodelet %s", name.c_str()); - return true; } catch(...) { Impl::M_stringToNodelet::iterator it = impl_->nodelets_.find(name); if (it != impl_->nodelets_.end()) @@ -326,6 +325,7 @@ return (false); } } + return true; } bool Loader::unload (const std::string & name) diff -Nru ros-nodelet-core-1.9.8/nodelet/src/nodelet_class.cpp ros-nodelet-core-1.9.16/nodelet/src/nodelet_class.cpp --- ros-nodelet-core-1.9.8/nodelet/src/nodelet_class.cpp 2016-11-15 15:32:47.000000000 +0000 +++ ros-nodelet-core-1.9.16/nodelet/src/nodelet_class.cpp 2018-11-03 12:16:03.000000000 +0000 @@ -113,6 +113,7 @@ } nodelet_name_ = name; + remapping_args_ = remapping_args; my_argv_ = my_argv; // Set up NodeHandles with correct namespaces @@ -127,7 +128,7 @@ nh_->setCallbackQueue(st_queue); mt_private_nh_->setCallbackQueue(mt_queue); mt_nh_->setCallbackQueue(mt_queue); - + NODELET_DEBUG ("Nodelet initializing"); inited_ = true; this->onInit (); diff -Nru ros-nodelet-core-1.9.8/nodelet/src/nodelet.cpp ros-nodelet-core-1.9.16/nodelet/src/nodelet.cpp --- ros-nodelet-core-1.9.8/nodelet/src/nodelet.cpp 2016-11-15 15:32:47.000000000 +0000 +++ ros-nodelet-core-1.9.16/nodelet/src/nodelet.cpp 2018-11-03 12:16:03.000000000 +0000 @@ -72,7 +72,7 @@ std::string manager_; std::vector local_args_; bool is_bond_enabled_; - + public: //NodeletArgumentParsing() { }; bool @@ -106,15 +106,16 @@ else if (command_ == "unload" && non_ros_args.size() > 3) { - name_ = non_ros_args[2]; - manager_ = non_ros_args[3]; - used_args = 4; + type_ = "nodelet_unloader"; + name_ = non_ros_args[2]; + manager_ = non_ros_args[3]; + used_args = 4; } else if (command_ == "standalone" && non_ros_args.size() > 2) { - type_ = non_ros_args[2]; - printf("type is %s\n", type_.c_str()); - used_args = 3; + type_ = non_ros_args[2]; + printf("type is %s\n", type_.c_str()); + used_args = 3; } if (command_ == "manager") @@ -241,14 +242,14 @@ printf("\nnodelet usage:\n"); printf("nodelet load pkg/Type manager [--no-bond] - Launch a nodelet of type pkg/Type on manager manager\n"); printf("nodelet standalone pkg/Type - Launch a nodelet of type pkg/Type in a standalone node\n"); - printf("nodelet unload name manager - Unload a nodelet a nodelet by name from manager\n"); + printf("nodelet unload name manager - Unload a nodelet by name from manager\n"); printf("nodelet manager - Launch a nodelet manager node\n"); }; sig_atomic_t volatile request_shutdown = 0; -void nodeletLoaderSigIntHandler(int sig) +void nodeletLoaderSigIntHandler(int) { request_shutdown = 1; } @@ -327,7 +328,7 @@ signal(SIGINT, nodeletLoaderSigIntHandler); ros::XMLRPCManager::instance()->unbind("shutdown"); ros::XMLRPCManager::instance()->bind("shutdown", shutdownCallback); - + if (arg_parser.isBondEnabled()) bond.start(); // Spin our own loop diff -Nru ros-nodelet-core-1.9.8/nodelet_core/CHANGELOG.rst ros-nodelet-core-1.9.16/nodelet_core/CHANGELOG.rst --- ros-nodelet-core-1.9.8/nodelet_core/CHANGELOG.rst 2016-11-15 15:32:47.000000000 +0000 +++ ros-nodelet-core-1.9.16/nodelet_core/CHANGELOG.rst 2018-11-03 12:16:03.000000000 +0000 @@ -2,6 +2,33 @@ Changelog for package nodelet_core ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.9.16 (2018-04-27) +------------------- + +1.9.15 (2018-03-16) +------------------- + +1.9.14 (2017-11-15) +------------------- + +1.9.13 (2017-10-27) +------------------- + +1.9.12 (2017-08-04) +------------------- + +1.9.11 (2017-07-27) +------------------- +* remove trailing whitespaces (`#62 `_) +* switch to package format 2 (`#63 `_) +* Contributors: Mikael Arguedas + +1.9.10 (2017-03-27) +------------------- + +1.9.9 (2017-02-17) +------------------ + 1.9.8 (2016-11-15) ------------------ diff -Nru ros-nodelet-core-1.9.8/nodelet_core/package.xml ros-nodelet-core-1.9.16/nodelet_core/package.xml --- ros-nodelet-core-1.9.8/nodelet_core/package.xml 2016-11-15 15:32:47.000000000 +0000 +++ ros-nodelet-core-1.9.16/nodelet_core/package.xml 2018-11-03 12:16:03.000000000 +0000 @@ -1,21 +1,23 @@ - + + + nodelet_core - 1.9.8 + 1.9.16 Nodelet Core Metapackage Mikael Arguedas BSD - + http://www.ros.org/wiki/nodelet_core https://github.com/ros/nodelet_core/issues https://github.com/ros/nodelet_core - + Tully Foote - + catkin - nodelet - nodelet_topic_tools + nodelet + nodelet_topic_tools diff -Nru ros-nodelet-core-1.9.8/nodelet_topic_tools/CHANGELOG.rst ros-nodelet-core-1.9.16/nodelet_topic_tools/CHANGELOG.rst --- ros-nodelet-core-1.9.8/nodelet_topic_tools/CHANGELOG.rst 2016-11-15 15:32:47.000000000 +0000 +++ ros-nodelet-core-1.9.16/nodelet_topic_tools/CHANGELOG.rst 2018-11-03 12:16:03.000000000 +0000 @@ -2,6 +2,37 @@ Changelog for package nodelet_topic_tools ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.9.16 (2018-04-27) +------------------- + +1.9.15 (2018-03-16) +------------------- +* use new pluginlib headers (`#73 `_) +* Contributors: Mikael Arguedas + +1.9.14 (2017-11-15) +------------------- + +1.9.13 (2017-10-27) +------------------- + +1.9.12 (2017-08-04) +------------------- +* fix exec_depend that are actually build_export_depends (`#65 `_) +* Contributors: Mikael Arguedas + +1.9.11 (2017-07-27) +------------------- +* remove trailing whitespaces (`#62 `_) +* switch to package format 2 (`#63 `_) +* Contributors: Mikael Arguedas + +1.9.10 (2017-03-27) +------------------- + +1.9.9 (2017-02-17) +------------------ + 1.9.8 (2016-11-15) ------------------ diff -Nru ros-nodelet-core-1.9.8/nodelet_topic_tools/include/nodelet_topic_tools/nodelet_demux.h ros-nodelet-core-1.9.16/nodelet_topic_tools/include/nodelet_topic_tools/nodelet_demux.h --- ros-nodelet-core-1.9.8/nodelet_topic_tools/include/nodelet_topic_tools/nodelet_demux.h 2016-11-15 15:32:47.000000000 +0000 +++ ros-nodelet-core-1.9.16/nodelet_topic_tools/include/nodelet_topic_tools/nodelet_demux.h 2018-11-03 12:16:03.000000000 +0000 @@ -63,7 +63,7 @@ if (!private_nh_.getParam ("output_topics", output_topics_)) { ROS_ERROR ("[nodelet::NodeletDEMUX::init] Need a 'output_topics' parameter to be set before continuing!"); - return; + return; } // Check the type switch (output_topics_.getType ()) @@ -115,7 +115,7 @@ std::vector > pubs_output_; /** \brief The input subscriber. */ Subscriber sub_input_; - + /** \brief The list of output topics passed as a parameter. */ XmlRpc::XmlRpcValue output_topics_; @@ -141,7 +141,7 @@ if (!private_nh_.getParam ("output_topics", output_topics_)) { ROS_ERROR ("[nodelet::NodeletDEMUX::init] Need a 'output_topics' parameter to be set before continuing!"); - return; + return; } // Check the type switch (output_topics_.getType ()) @@ -193,7 +193,7 @@ std::vector > pubs_output_; /** \brief The input subscriber. */ ros::Subscriber sub_input_; - + /** \brief The list of output topics passed as a parameter. */ XmlRpc::XmlRpcValue output_topics_; diff -Nru ros-nodelet-core-1.9.8/nodelet_topic_tools/include/nodelet_topic_tools/nodelet_mux.h ros-nodelet-core-1.9.16/nodelet_topic_tools/include/nodelet_topic_tools/nodelet_mux.h --- ros-nodelet-core-1.9.8/nodelet_topic_tools/include/nodelet_topic_tools/nodelet_mux.h 2016-11-15 15:32:47.000000000 +0000 +++ ros-nodelet-core-1.9.16/nodelet_topic_tools/include/nodelet_topic_tools/nodelet_mux.h 2018-11-03 12:16:03.000000000 +0000 @@ -44,7 +44,7 @@ namespace nodelet { - /** \brief @b NodeletMUX represent a mux nodelet for topics: it takes N (<=8) input topics, and publishes all of them + /** \brief @b NodeletMUX represent a mux nodelet for topics: it takes N (<=8) input topics, and publishes all of them * on one output topic. * \author Radu Bogdan Rusu */ @@ -53,9 +53,8 @@ { typedef typename boost::shared_ptr TPtr; typedef typename boost::shared_ptr TConstPtr; - + public: - NodeletMUX () : maximum_queue_size_ (3) {} ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// @@ -70,11 +69,11 @@ if (!private_nh_.getParam ("input_topics", input_topics)) { ROS_ERROR ("[nodelet::NodeletMUX::init] Need a 'input_topics' parameter to be set before continuing!"); - return; + return; } - + private_nh_.getParam ("max_queue_size", maximum_queue_size_); - + // Check the type switch (input_topics.getType ()) { @@ -108,7 +107,7 @@ filters_[0]->registerCallback (boost::bind (&NodeletMUX::filter_cb, this, _1)); ts_.reset (new message_filters::TimeSynchronizer (maximum_queue_size_)); - + switch (input_topics.size ()) { case 2: @@ -160,7 +159,7 @@ return; } } - + ts_->registerCallback (boost::bind (&NodeletMUX::input, this, _1, _2, _3, _4, _5, _6, _7, _8)); } @@ -172,12 +171,12 @@ nf_.add (input); } - void - input (const TConstPtr &in1, const TConstPtr &in2, const TConstPtr &in3, const TConstPtr &in4, + void + input (const TConstPtr &in1, const TConstPtr &in2, const TConstPtr &in3, const TConstPtr &in4, const TConstPtr &in5, const TConstPtr &in6, const TConstPtr &in7, const TConstPtr &in8) - { - pub_output_.publish (in1); pub_output_.publish (in2); pub_output_.publish (in3); pub_output_.publish (in4); - pub_output_.publish (in5); pub_output_.publish (in6); pub_output_.publish (in7); pub_output_.publish (in8); + { + pub_output_.publish (in1); pub_output_.publish (in2); pub_output_.publish (in3); pub_output_.publish (in4); + pub_output_.publish (in5); pub_output_.publish (in6); pub_output_.publish (in7); pub_output_.publish (in8); } /** \brief ROS local node handle. */ @@ -190,7 +189,7 @@ /** \brief The maximum number of messages that we can store in the queue. */ int maximum_queue_size_; - + /** \brief A vector of message filters. */ std::vector > filters_; diff -Nru ros-nodelet-core-1.9.8/nodelet_topic_tools/include/nodelet_topic_tools/nodelet_throttle.h ros-nodelet-core-1.9.16/nodelet_topic_tools/include/nodelet_topic_tools/nodelet_throttle.h --- ros-nodelet-core-1.9.8/nodelet_topic_tools/include/nodelet_topic_tools/nodelet_throttle.h 2016-11-15 15:32:47.000000000 +0000 +++ ros-nodelet-core-1.9.16/nodelet_topic_tools/include/nodelet_topic_tools/nodelet_throttle.h 2018-11-03 12:16:03.000000000 +0000 @@ -31,7 +31,7 @@ */ #include -#include +#include #include #include #include diff -Nru ros-nodelet-core-1.9.8/nodelet_topic_tools/package.xml ros-nodelet-core-1.9.16/nodelet_topic_tools/package.xml --- ros-nodelet-core-1.9.8/nodelet_topic_tools/package.xml 2016-11-15 15:32:47.000000000 +0000 +++ ros-nodelet-core-1.9.16/nodelet_topic_tools/package.xml 2018-11-03 12:16:03.000000000 +0000 @@ -1,6 +1,8 @@ - + + + nodelet_topic_tools - 1.9.8 + 1.9.16 This package contains common nodelet tools such as a mux, demux and throttle. @@ -15,13 +17,11 @@ catkin - boost - dynamic_reconfigure + boost + dynamic_reconfigure - boost - dynamic_reconfigure - message_filters - nodelet - pluginlib - roscpp + message_filters + nodelet + pluginlib + roscpp diff -Nru ros-nodelet-core-1.9.8/test_nodelet/CHANGELOG.rst ros-nodelet-core-1.9.16/test_nodelet/CHANGELOG.rst --- ros-nodelet-core-1.9.8/test_nodelet/CHANGELOG.rst 2016-11-15 15:32:47.000000000 +0000 +++ ros-nodelet-core-1.9.16/test_nodelet/CHANGELOG.rst 2018-11-03 12:16:03.000000000 +0000 @@ -2,6 +2,40 @@ Changelog for package test_nodelet ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.9.16 (2018-04-27) +------------------- + +1.9.15 (2018-03-16) +------------------- +* use new pluginlib headers (`#73 `_) +* Contributors: Mikael Arguedas + +1.9.14 (2017-11-15) +------------------- +* update to use non deprecated pluginlib macro (`#69 `_) +* Contributors: Mikael Arguedas + +1.9.13 (2017-10-27) +------------------- + +1.9.12 (2017-08-04) +------------------- + +1.9.11 (2017-07-27) +------------------- +* Test nodehandles (`#64 `_) +* remove trailing whitespaces (`#62 `_) +* switch to package format 2 (`#63 `_) +* Contributors: Mikael Arguedas + +1.9.10 (2017-03-27) +------------------- +* fix unused var warning +* Contributors: Mikael Arguedas + +1.9.9 (2017-02-17) +------------------ + 1.9.8 (2016-11-15) ------------------ * Fix bond handling during nodelet unloading (`#51 `_) diff -Nru ros-nodelet-core-1.9.8/test_nodelet/CMakeLists.txt ros-nodelet-core-1.9.16/test_nodelet/CMakeLists.txt --- ros-nodelet-core-1.9.8/test_nodelet/CMakeLists.txt 2016-11-15 15:32:47.000000000 +0000 +++ ros-nodelet-core-1.9.16/test_nodelet/CMakeLists.txt 2018-11-03 12:16:03.000000000 +0000 @@ -13,7 +13,7 @@ ) #common commands for building c++ executables and libraries - add_library(${PROJECT_NAME} src/plus.cpp src/console_tests.cpp src/failing_nodelet.cpp) + add_library(${PROJECT_NAME} src/plus.cpp src/console_tests.cpp src/failing_nodelet.cpp src/nodehandles.cpp) target_link_libraries(${PROJECT_NAME} ${BOOST_LIBRARIES} ${catkin_LIBRARIES} ) @@ -32,6 +32,21 @@ add_rostest(test/test_bond_break_on_shutdown.launch) add_rostest(test/test_unload_called_twice.launch) + add_rostest_gtest(test_nodehandles_different_namespaces + test/test_nodehandles_different_namespaces.test + test/test_nodehandles_different_namespaces.cpp) + target_link_libraries(test_nodehandles_different_namespaces ${catkin_LIBRARIES}) + + add_rostest_gtest(test_nodehandles_same_namespaces + test/test_nodehandles_same_namespaces.test + test/test_nodehandles_same_namespaces.cpp) + target_link_libraries(test_nodehandles_same_namespaces ${catkin_LIBRARIES}) + + add_rostest_gtest(test_nodehandles_manager_namespaced + test/test_nodehandles_manager_namespaced.test + test/test_nodehandles_manager_namespaced.cpp) + target_link_libraries(test_nodehandles_manager_namespaced ${catkin_LIBRARIES}) + # Not a real test. Tries to measure overhead of CallbackQueueManager. add_executable(benchmark src/benchmark.cpp) target_link_libraries(benchmark ${BOOST_LIBRARIES} diff -Nru ros-nodelet-core-1.9.8/test_nodelet/package.xml ros-nodelet-core-1.9.16/test_nodelet/package.xml --- ros-nodelet-core-1.9.8/test_nodelet/package.xml 2016-11-15 15:32:47.000000000 +0000 +++ ros-nodelet-core-1.9.16/test_nodelet/package.xml 2018-11-03 12:16:03.000000000 +0000 @@ -1,6 +1,8 @@ - + + + test_nodelet - 1.9.8 + 1.9.16 A package for nodelet unit tests @@ -14,15 +16,10 @@ catkin - nodelet - pluginlib - rostest - std_msgs - - nodelet - pluginlib - rostest - std_msgs + nodelet + pluginlib + rostest + std_msgs rosbash diff -Nru ros-nodelet-core-1.9.8/test_nodelet/src/benchmark.cpp ros-nodelet-core-1.9.16/test_nodelet/src/benchmark.cpp --- ros-nodelet-core-1.9.8/test_nodelet/src/benchmark.cpp 2016-11-15 15:32:47.000000000 +0000 +++ ros-nodelet-core-1.9.16/test_nodelet/src/benchmark.cpp 2018-11-03 12:16:03.000000000 +0000 @@ -39,7 +39,7 @@ man.addQueue(queue, true); double start = ros::WallTime::now().toSec(); - + for (long i = 0; i < NUM_CALLBACKS; ++i) { MyCallbackPtr cb(new MyCallback); diff -Nru ros-nodelet-core-1.9.8/test_nodelet/src/console_tests.cpp ros-nodelet-core-1.9.16/test_nodelet/src/console_tests.cpp --- ros-nodelet-core-1.9.8/test_nodelet/src/console_tests.cpp 2016-11-15 15:32:47.000000000 +0000 +++ ros-nodelet-core-1.9.16/test_nodelet/src/console_tests.cpp 2018-11-03 12:16:03.000000000 +0000 @@ -1,10 +1,10 @@ /* * Copyright (c) 2009, 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 @@ -13,7 +13,7 @@ * * Neither the name of the 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 @@ -27,7 +27,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include +#include #include #include #include @@ -180,11 +180,9 @@ //TODO TEST FILTERS //NODELET_FATAL_FILTER_NAMED(10.0, suffix, "FATAL named output"); //NODELET_FATAL_STREAM_FILTER_NAMED(10.0, suffix, "FATAL" << " named output"); - - } }; -PLUGINLIB_DECLARE_CLASS(test_nodelet, ConsoleTest, test_nodelet::ConsoleTest, nodelet::Nodelet); +PLUGINLIB_EXPORT_CLASS(test_nodelet::ConsoleTest, nodelet::Nodelet) } diff -Nru ros-nodelet-core-1.9.8/test_nodelet/src/create_instance_cb_error.cpp ros-nodelet-core-1.9.16/test_nodelet/src/create_instance_cb_error.cpp --- ros-nodelet-core-1.9.8/test_nodelet/src/create_instance_cb_error.cpp 2016-11-15 15:32:47.000000000 +0000 +++ ros-nodelet-core-1.9.16/test_nodelet/src/create_instance_cb_error.cpp 2018-11-03 12:16:03.000000000 +0000 @@ -35,7 +35,7 @@ #include -boost::shared_ptr create_instance(const std::string& lookup_name) +boost::shared_ptr create_instance(const std::string&) { throw std::runtime_error("NODELET_TEST_FAILURE"); } diff -Nru ros-nodelet-core-1.9.8/test_nodelet/src/failing_nodelet.cpp ros-nodelet-core-1.9.16/test_nodelet/src/failing_nodelet.cpp --- ros-nodelet-core-1.9.8/test_nodelet/src/failing_nodelet.cpp 2016-11-15 15:32:47.000000000 +0000 +++ ros-nodelet-core-1.9.16/test_nodelet/src/failing_nodelet.cpp 2018-11-03 12:16:03.000000000 +0000 @@ -27,7 +27,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include +#include #include #include @@ -47,5 +47,5 @@ } }; -PLUGINLIB_DECLARE_CLASS(test_nodelet, FailingNodelet, test_nodelet::FailingNodelet, nodelet::Nodelet); +PLUGINLIB_EXPORT_CLASS(test_nodelet::FailingNodelet, nodelet::Nodelet) } diff -Nru ros-nodelet-core-1.9.8/test_nodelet/src/nodehandles.cpp ros-nodelet-core-1.9.16/test_nodelet/src/nodehandles.cpp --- ros-nodelet-core-1.9.8/test_nodelet/src/nodehandles.cpp 1970-01-01 00:00:00.000000000 +0000 +++ ros-nodelet-core-1.9.16/test_nodelet/src/nodehandles.cpp 2018-11-03 12:16:03.000000000 +0000 @@ -0,0 +1,30 @@ +#include +#include +#include +#include +#include +#include +#include + +namespace test_nodelet +{ + +class NodehandleTest : public nodelet::Nodelet +{ +public: + NodehandleTest(){}; + virtual void onInit() + { + ros::NodeHandle nh = this->getNodeHandle(); + ros::NodeHandle pnh = this->getPrivateNodeHandle(); + global_pub_ = nh.advertise("/global", 1000); + namespaced_pub_ = nh.advertise("namespaced", 1000); + private_pub_ = pnh.advertise("private", 1000); + } +private: + ros::Publisher global_pub_, namespaced_pub_, private_pub_; +}; + +} // namespace test_nodelet + +PLUGINLIB_EXPORT_CLASS(test_nodelet::NodehandleTest, nodelet::Nodelet); diff -Nru ros-nodelet-core-1.9.8/test_nodelet/src/plus.cpp ros-nodelet-core-1.9.16/test_nodelet/src/plus.cpp --- ros-nodelet-core-1.9.8/test_nodelet/src/plus.cpp 2016-11-15 15:32:47.000000000 +0000 +++ ros-nodelet-core-1.9.16/test_nodelet/src/plus.cpp 2018-11-03 12:16:03.000000000 +0000 @@ -1,10 +1,10 @@ /* * Copyright (c) 2009, 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 @@ -13,7 +13,7 @@ * * Neither the name of the 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 @@ -27,7 +27,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include +#include #include #include #include @@ -68,5 +68,5 @@ double value_; }; -PLUGINLIB_DECLARE_CLASS(test_nodelet, Plus, test_nodelet::Plus, nodelet::Nodelet); +PLUGINLIB_EXPORT_CLASS(test_nodelet::Plus, nodelet::Nodelet) } diff -Nru ros-nodelet-core-1.9.8/test_nodelet/test/plus_local.py ros-nodelet-core-1.9.16/test_nodelet/test/plus_local.py --- ros-nodelet-core-1.9.8/test_nodelet/test/plus_local.py 2016-11-15 15:32:47.000000000 +0000 +++ ros-nodelet-core-1.9.16/test_nodelet/test/plus_local.py 2018-11-03 12:16:03.000000000 +0000 @@ -2,10 +2,10 @@ # Copyright (c) 2009, 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 @@ -14,7 +14,7 @@ # * Neither the name of the 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 @@ -52,7 +52,7 @@ if self.recieved == True: break rospy.sleep(1.0) - return self.result + return self.result def callback(self, data): rospy.loginfo(rospy.get_name()+" I heard %s which was a change of %f",data.data, data.data-self.send_value) diff -Nru ros-nodelet-core-1.9.8/test_nodelet/test/test_console.launch ros-nodelet-core-1.9.16/test_nodelet/test/test_console.launch --- ros-nodelet-core-1.9.8/test_nodelet/test/test_console.launch 2016-11-15 15:32:47.000000000 +0000 +++ ros-nodelet-core-1.9.16/test_nodelet/test/test_console.launch 2018-11-03 12:16:03.000000000 +0000 @@ -1,4 +1,3 @@ - - + diff -Nru ros-nodelet-core-1.9.8/test_nodelet/test/test_loader.py ros-nodelet-core-1.9.16/test_nodelet/test/test_loader.py --- ros-nodelet-core-1.9.8/test_nodelet/test/test_loader.py 2016-11-15 15:32:47.000000000 +0000 +++ ros-nodelet-core-1.9.16/test_nodelet/test/test_loader.py 2018-11-03 12:16:03.000000000 +0000 @@ -2,10 +2,10 @@ # Copyright (c) 2009, 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 @@ -14,7 +14,7 @@ # * Neither the name of the 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 @@ -42,22 +42,22 @@ load = rospy.ServiceProxy('/nodelet_manager/load_nodelet', NodeletLoad) unload = rospy.ServiceProxy('/nodelet_manager/unload_nodelet', NodeletUnload) list = rospy.ServiceProxy('/nodelet_manager/list', NodeletList) - + load.wait_for_service() unload.wait_for_service() list.wait_for_service() - + req = NodeletLoadRequest() req.name = "/my_nodelet" req.type = "test_nodelet/Plus" - + res = load.call(req) self.assertTrue(res.success) - + req = NodeletListRequest() res = list.call(req) self.assertTrue("/my_nodelet" in res.nodelets) - + req = NodeletUnloadRequest() req.name = "/my_nodelet" res = unload.call(req) diff -Nru ros-nodelet-core-1.9.8/test_nodelet/test/test_nodehandles_different_namespaces.cpp ros-nodelet-core-1.9.16/test_nodelet/test/test_nodehandles_different_namespaces.cpp --- ros-nodelet-core-1.9.8/test_nodelet/test/test_nodehandles_different_namespaces.cpp 1970-01-01 00:00:00.000000000 +0000 +++ ros-nodelet-core-1.9.16/test_nodelet/test/test_nodehandles_different_namespaces.cpp 2018-11-03 12:16:03.000000000 +0000 @@ -0,0 +1,154 @@ +/********************************************************************* +* test_nodehandles_different_namespaces.cpp +* +* Software License Agreement (BSD License) +* +* Copyright (c) 2016, University of Patras +* 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 University of Patras 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. +* +* Authors: Aris Synodinos +*********************************************************************/ + +#include +#include +#include +#include +#include +#include +#include +#include + +TEST(DifferentNamespaces, NodeletPrivateNodehandle) { + ros::NodeHandle nh; + ros::Duration(2).sleep(); + ros::master::V_TopicInfo master_topics; + ros::master::getTopics(master_topics); + bool found_topic = false; + + for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) { + const ros::master::TopicInfo& info = *it; + if (info.datatype.compare("std_msgs/Bool") == 0) { + found_topic = true; + EXPECT_STREQ("/nodelet_namespace/nodehandle_test/private", info.name.c_str()); + } + } + EXPECT_TRUE(found_topic); +} + +TEST(DifferentNamespaces, NodeletNamespacedNodehandle) { + ros::NodeHandle nh; + ros::Duration(2).sleep(); + ros::master::V_TopicInfo master_topics; + ros::master::getTopics(master_topics); + bool found_topic = false; + + for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) { + const ros::master::TopicInfo& info = *it; + if (info.datatype.compare("std_msgs/Byte") == 0) { + found_topic = true; + EXPECT_STREQ("/nodelet_namespace/namespaced", info.name.c_str()); + } + } + EXPECT_TRUE(found_topic); +} + +TEST(DifferentNamespaces, NodeletGlobalNodehandle) { + ros::NodeHandle nh; + ros::Duration(2).sleep(); + ros::master::V_TopicInfo master_topics; + ros::master::getTopics(master_topics); + bool found_topic = false; + + for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) { + const ros::master::TopicInfo& info = *it; + if (info.datatype.compare("std_msgs/Time") == 0) { + found_topic = true; + EXPECT_STREQ("/global", info.name.c_str()); + } + } + EXPECT_TRUE(found_topic); +} + +TEST(DifferentNamespaces, NodePrivateNodehandle) { + ros::NodeHandle nh("~"); + ros::Publisher pub = nh.advertise("private", 10); + ros::master::V_TopicInfo master_topics; + ros::master::getTopics(master_topics); + bool found_topic = false; + + for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) { + const ros::master::TopicInfo& info = *it; + if (info.datatype.compare("std_msgs/Empty") == 0) { + found_topic = true; + EXPECT_STREQ("/test_namespace/test_nodehandles/private", info.name.c_str()); + } + } + EXPECT_TRUE(found_topic); +} + +TEST(DifferentNamespaces, NodeNamespacedNodehandle) { + ros::NodeHandle nh; + ros::Publisher pub = nh.advertise("namespaced", 10); + ros::master::V_TopicInfo master_topics; + ros::master::getTopics(master_topics); + bool found_topic = false; + + for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) { + const ros::master::TopicInfo& info = *it; + if (info.datatype.compare("std_msgs/String") == 0) { + found_topic = true; + EXPECT_STREQ("/test_namespace/namespaced", info.name.c_str()); + } + } + EXPECT_TRUE(found_topic); +} + +TEST(DifferentNamespaces, NodeGlobalNodehandle) { + ros::NodeHandle nh; + ros::Publisher pub = nh.advertise("/public", 10); + ros::master::V_TopicInfo master_topics; + ros::master::getTopics(master_topics); + bool found_topic = false; + + for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) { + const ros::master::TopicInfo& info = *it; + if (info.datatype.compare("std_msgs/Float32") == 0) { + found_topic = true; + EXPECT_STREQ("/public", info.name.c_str()); + } + } + EXPECT_TRUE(found_topic); +} + +int main(int argc, char **argv) { + testing::InitGoogleTest(&argc, argv); + ros::init(argc, argv, "test_nodehandles_different_namespaces"); + return RUN_ALL_TESTS(); +} diff -Nru ros-nodelet-core-1.9.8/test_nodelet/test/test_nodehandles_different_namespaces.test ros-nodelet-core-1.9.16/test_nodelet/test/test_nodehandles_different_namespaces.test --- ros-nodelet-core-1.9.8/test_nodelet/test/test_nodehandles_different_namespaces.test 1970-01-01 00:00:00.000000000 +0000 +++ ros-nodelet-core-1.9.16/test_nodelet/test/test_nodehandles_different_namespaces.test 2018-11-03 12:16:03.000000000 +0000 @@ -0,0 +1,12 @@ + + + + + + + + + + + + diff -Nru ros-nodelet-core-1.9.8/test_nodelet/test/test_nodehandles_manager_namespaced.cpp ros-nodelet-core-1.9.16/test_nodelet/test/test_nodehandles_manager_namespaced.cpp --- ros-nodelet-core-1.9.8/test_nodelet/test/test_nodehandles_manager_namespaced.cpp 1970-01-01 00:00:00.000000000 +0000 +++ ros-nodelet-core-1.9.16/test_nodelet/test/test_nodehandles_manager_namespaced.cpp 2018-11-03 12:16:03.000000000 +0000 @@ -0,0 +1,155 @@ +/********************************************************************* +* test_nodehandles_same_namespaces.cpp +* +* Software License Agreement (BSD License) +* +* Copyright (c) 2016, University of Patras +* 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 University of Patras 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. +* +* Authors: Aris Synodinos +*********************************************************************/ + +#include +#include +#include +#include +#include +#include +#include + +TEST(ManagerNamespaced, NodeletPrivateNodehandle) { + ros::NodeHandle nh; + ros::Duration(2).sleep(); + ros::master::V_TopicInfo master_topics; + ros::master::getTopics(master_topics); + bool found_topic = false; + + for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) { + const ros::master::TopicInfo& info = *it; + if (info.datatype.compare("std_msgs/Bool") == 0) { + found_topic = true; + EXPECT_STREQ("/nodehandle_test/private", info.name.c_str()); + } + } + EXPECT_TRUE(found_topic); +} + +// TODO(mikaelarguedas) reenable this once +// https://github.com/ros/nodelet_core/issues/7 is fixed +// TEST(ManagerNamespaced, NodeletNamespacedNodehandle) { +// ros::NodeHandle nh; +// ros::Duration(2).sleep(); +// ros::master::V_TopicInfo master_topics; +// ros::master::getTopics(master_topics); +// bool found_topic = false; +// +// for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) { +// const ros::master::TopicInfo& info = *it; +// if (info.datatype.compare("std_msgs/Byte") == 0) { +// found_topic = true; +// EXPECT_STREQ("/namespaced", info.name.c_str()); +// } +// } +// EXPECT_TRUE(found_topic); +// } + +TEST(ManagerNamespaced, NodeletGlobalNodehandle) { + ros::NodeHandle nh; + ros::Duration(2).sleep(); + ros::master::V_TopicInfo master_topics; + ros::master::getTopics(master_topics); + bool found_topic = false; + + for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) { + const ros::master::TopicInfo& info = *it; + if (info.datatype.compare("std_msgs/Time") == 0) { + found_topic = true; + EXPECT_STREQ("/global", info.name.c_str()); + } + } + EXPECT_TRUE(found_topic); +} + +TEST(ManagerNamespaced, NodePrivateNodehandle) { + ros::NodeHandle nh("~"); + ros::Publisher pub = nh.advertise("private", 10); + ros::master::V_TopicInfo master_topics; + ros::master::getTopics(master_topics); + bool found_topic = false; + + for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) { + const ros::master::TopicInfo& info = *it; + if (info.datatype.compare("std_msgs/Empty") == 0) { + found_topic = true; + EXPECT_STREQ("/test_nodehandles/private", info.name.c_str()); + } + } + EXPECT_TRUE(found_topic); +} + +TEST(ManagerNamespaced, NodeNamespacedNodehandle) { + ros::NodeHandle nh; + ros::Publisher pub = nh.advertise("namespaced", 10); + ros::master::V_TopicInfo master_topics; + ros::master::getTopics(master_topics); + bool found_topic = false; + + for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) { + const ros::master::TopicInfo& info = *it; + if (info.datatype.compare("std_msgs/String") == 0) { + found_topic = true; + EXPECT_STREQ("/namespaced", info.name.c_str()); + } + } + EXPECT_TRUE(found_topic); +} + +TEST(ManagerNamespaced, NodeGlobalNodehandle) { + ros::NodeHandle nh; + ros::Publisher pub = nh.advertise("/public", 10); + ros::master::V_TopicInfo master_topics; + ros::master::getTopics(master_topics); + bool found_topic = false; + + for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) { + const ros::master::TopicInfo& info = *it; + if (info.datatype.compare("std_msgs/Float32") == 0) { + found_topic = true; + EXPECT_STREQ("/public", info.name.c_str()); + } + } + EXPECT_TRUE(found_topic); +} + +int main(int argc, char **argv) { + testing::InitGoogleTest(&argc, argv); + ros::init(argc, argv, "test_nodehandles_manager_namespaced"); + return RUN_ALL_TESTS(); +} diff -Nru ros-nodelet-core-1.9.8/test_nodelet/test/test_nodehandles_manager_namespaced.test ros-nodelet-core-1.9.16/test_nodelet/test/test_nodehandles_manager_namespaced.test --- ros-nodelet-core-1.9.8/test_nodelet/test/test_nodehandles_manager_namespaced.test 1970-01-01 00:00:00.000000000 +0000 +++ ros-nodelet-core-1.9.16/test_nodelet/test/test_nodehandles_manager_namespaced.test 2018-11-03 12:16:03.000000000 +0000 @@ -0,0 +1,9 @@ + + + + + + + + + diff -Nru ros-nodelet-core-1.9.8/test_nodelet/test/test_nodehandles_same_namespaces.cpp ros-nodelet-core-1.9.16/test_nodelet/test/test_nodehandles_same_namespaces.cpp --- ros-nodelet-core-1.9.8/test_nodelet/test/test_nodehandles_same_namespaces.cpp 1970-01-01 00:00:00.000000000 +0000 +++ ros-nodelet-core-1.9.16/test_nodelet/test/test_nodehandles_same_namespaces.cpp 2018-11-03 12:16:03.000000000 +0000 @@ -0,0 +1,153 @@ +/********************************************************************* +* test_nodehandles_same_namespaces.cpp +* +* Software License Agreement (BSD License) +* +* Copyright (c) 2016, University of Patras +* 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 University of Patras 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. +* +* Authors: Aris Synodinos +*********************************************************************/ + +#include +#include +#include +#include +#include +#include +#include + +TEST(SameNamespaces, NodeletPrivateNodehandle) { + ros::NodeHandle nh; + ros::Duration(2).sleep(); + ros::master::V_TopicInfo master_topics; + ros::master::getTopics(master_topics); + bool found_topic = false; + + for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) { + const ros::master::TopicInfo& info = *it; + if (info.datatype.compare("std_msgs/Bool") == 0) { + found_topic = true; + EXPECT_STREQ("/common_namespace/nodehandle_test/private", info.name.c_str()); + } + } + EXPECT_TRUE(found_topic); +} + +TEST(SameNamespaces, NodeletNamespacedNodehandle) { + ros::NodeHandle nh; + ros::Duration(2).sleep(); + ros::master::V_TopicInfo master_topics; + ros::master::getTopics(master_topics); + bool found_topic = false; + + for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) { + const ros::master::TopicInfo& info = *it; + if (info.datatype.compare("std_msgs/Byte") == 0) { + found_topic = true; + EXPECT_STREQ("/common_namespace/namespaced", info.name.c_str()); + } + } + EXPECT_TRUE(found_topic); +} + +TEST(SameNamespaces, NodeletGlobalNodehandle) { + ros::NodeHandle nh; + ros::Duration(2).sleep(); + ros::master::V_TopicInfo master_topics; + ros::master::getTopics(master_topics); + bool found_topic = false; + + for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) { + const ros::master::TopicInfo& info = *it; + if (info.datatype.compare("std_msgs/Time") == 0) { + found_topic = true; + EXPECT_STREQ("/global", info.name.c_str()); + } + } + EXPECT_TRUE(found_topic); +} + +TEST(SameNamespaces, NodePrivateNodehandle) { + ros::NodeHandle nh("~"); + ros::Publisher pub = nh.advertise("private", 10); + ros::master::V_TopicInfo master_topics; + ros::master::getTopics(master_topics); + bool found_topic = false; + + for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) { + const ros::master::TopicInfo& info = *it; + if (info.datatype.compare("std_msgs/Empty") == 0) { + found_topic = true; + EXPECT_STREQ("/common_namespace/test_nodehandles/private", info.name.c_str()); + } + } + EXPECT_TRUE(found_topic); +} + +TEST(SameNamespaces, NodeNamespacedNodehandle) { + ros::NodeHandle nh; + ros::Publisher pub = nh.advertise("namespaced", 10); + ros::master::V_TopicInfo master_topics; + ros::master::getTopics(master_topics); + bool found_topic = false; + + for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) { + const ros::master::TopicInfo& info = *it; + if (info.datatype.compare("std_msgs/String") == 0) { + found_topic = true; + EXPECT_STREQ("/common_namespace/namespaced", info.name.c_str()); + } + } + EXPECT_TRUE(found_topic); +} + +TEST(SameNamespaces, NodeGlobalNodehandle) { + ros::NodeHandle nh; + ros::Publisher pub = nh.advertise("/public", 10); + ros::master::V_TopicInfo master_topics; + ros::master::getTopics(master_topics); + bool found_topic = false; + + for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) { + const ros::master::TopicInfo& info = *it; + if (info.datatype.compare("std_msgs/Float32") == 0) { + found_topic = true; + EXPECT_STREQ("/public", info.name.c_str()); + } + } + EXPECT_TRUE(found_topic); +} + +int main(int argc, char **argv) { + testing::InitGoogleTest(&argc, argv); + ros::init(argc, argv, "test_nodehandles_same_namespaces"); + return RUN_ALL_TESTS(); +} diff -Nru ros-nodelet-core-1.9.8/test_nodelet/test/test_nodehandles_same_namespaces.test ros-nodelet-core-1.9.16/test_nodelet/test/test_nodehandles_same_namespaces.test --- ros-nodelet-core-1.9.8/test_nodelet/test/test_nodehandles_same_namespaces.test 1970-01-01 00:00:00.000000000 +0000 +++ ros-nodelet-core-1.9.16/test_nodelet/test/test_nodehandles_same_namespaces.test 2018-11-03 12:16:03.000000000 +0000 @@ -0,0 +1,8 @@ + + + + + + + + diff -Nru ros-nodelet-core-1.9.8/test_nodelet/test_loader.launch ros-nodelet-core-1.9.16/test_nodelet/test_loader.launch --- ros-nodelet-core-1.9.8/test_nodelet/test_loader.launch 2016-11-15 15:32:47.000000000 +0000 +++ ros-nodelet-core-1.9.16/test_nodelet/test_loader.launch 2018-11-03 12:16:03.000000000 +0000 @@ -1,4 +1,4 @@ - + diff -Nru ros-nodelet-core-1.9.8/test_nodelet/test_local.launch ros-nodelet-core-1.9.16/test_nodelet/test_local.launch --- ros-nodelet-core-1.9.8/test_nodelet/test_local.launch 2016-11-15 15:32:47.000000000 +0000 +++ ros-nodelet-core-1.9.16/test_nodelet/test_local.launch 2018-11-03 12:16:03.000000000 +0000 @@ -1,14 +1,14 @@ - + - - + + - + diff -Nru ros-nodelet-core-1.9.8/test_nodelet/test_nodelet.xml ros-nodelet-core-1.9.16/test_nodelet/test_nodelet.xml --- ros-nodelet-core-1.9.8/test_nodelet/test_nodelet.xml 2016-11-15 15:32:47.000000000 +0000 +++ ros-nodelet-core-1.9.16/test_nodelet/test_nodelet.xml 2018-11-03 12:16:03.000000000 +0000 @@ -6,7 +6,7 @@ - Test nodelet rosconsole macros. + Test nodelet rosconsole macros. @@ -14,4 +14,9 @@ A node that fails to initialize properly. + + + A node that creates public and private nodehandles. + + diff -Nru ros-nodelet-core-1.9.8/test_nodelet_topic_tools/CHANGELOG.rst ros-nodelet-core-1.9.16/test_nodelet_topic_tools/CHANGELOG.rst --- ros-nodelet-core-1.9.8/test_nodelet_topic_tools/CHANGELOG.rst 2016-11-15 15:32:47.000000000 +0000 +++ ros-nodelet-core-1.9.16/test_nodelet_topic_tools/CHANGELOG.rst 2018-11-03 12:16:03.000000000 +0000 @@ -2,6 +2,38 @@ Changelog for package test_nodelet_topic_tools ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.9.16 (2018-04-27) +------------------- + +1.9.15 (2018-03-16) +------------------- +* use new pluginlib headers (`#73 `_) +* Contributors: Mikael Arguedas + +1.9.14 (2017-11-15) +------------------- +* update to use non deprecated pluginlib macro (`#69 `_) +* Contributors: Mikael Arguedas + +1.9.13 (2017-10-27) +------------------- + +1.9.12 (2017-08-04) +------------------- + +1.9.11 (2017-07-27) +------------------- +* remove trailing whitespaces (`#62 `_) +* switch to package format 2 (`#63 `_) +* Test laziness after disconnection (`#60 `_) +* Contributors: Kentaro Wada, Mikael Arguedas + +1.9.10 (2017-03-27) +------------------- + +1.9.9 (2017-02-17) +------------------ + 1.9.8 (2016-11-15) ------------------ diff -Nru ros-nodelet-core-1.9.8/test_nodelet_topic_tools/package.xml ros-nodelet-core-1.9.16/test_nodelet_topic_tools/package.xml --- ros-nodelet-core-1.9.8/test_nodelet_topic_tools/package.xml 2016-11-15 15:32:47.000000000 +0000 +++ ros-nodelet-core-1.9.16/test_nodelet_topic_tools/package.xml 2018-11-03 12:16:03.000000000 +0000 @@ -1,6 +1,8 @@ - + + + test_nodelet_topic_tools - 1.9.8 + 1.9.16 A package for nodelet_topic_tools unit tests. @@ -15,20 +17,14 @@ catkin - message_filters - nodelet - nodelet_topic_tools - pluginlib - roscpp rostest - std_msgs - message_filters - nodelet - nodelet_topic_tools - pluginlib - roscpp - std_msgs + message_filters + nodelet + nodelet_topic_tools + pluginlib + roscpp + std_msgs rospy diff -Nru ros-nodelet-core-1.9.8/test_nodelet_topic_tools/test/string_nodelet_lazy.cpp ros-nodelet-core-1.9.16/test_nodelet_topic_tools/test/string_nodelet_lazy.cpp --- ros-nodelet-core-1.9.8/test_nodelet_topic_tools/test/string_nodelet_lazy.cpp 2016-11-15 15:32:47.000000000 +0000 +++ ros-nodelet-core-1.9.16/test_nodelet_topic_tools/test/string_nodelet_lazy.cpp 2018-11-03 12:16:03.000000000 +0000 @@ -75,5 +75,5 @@ } // namespace test_nodelet_topic_tools -#include +#include PLUGINLIB_EXPORT_CLASS(test_nodelet_topic_tools::NodeletLazyString, nodelet::Nodelet); diff -Nru ros-nodelet-core-1.9.8/test_nodelet_topic_tools/test/string_nodelet_throttle.cpp ros-nodelet-core-1.9.16/test_nodelet_topic_tools/test/string_nodelet_throttle.cpp --- ros-nodelet-core-1.9.8/test_nodelet_topic_tools/test/string_nodelet_throttle.cpp 2016-11-15 15:32:47.000000000 +0000 +++ ros-nodelet-core-1.9.16/test_nodelet_topic_tools/test/string_nodelet_throttle.cpp 2018-11-03 12:16:03.000000000 +0000 @@ -1,10 +1,10 @@ #include #include -#include +#include namespace test_nodelet_topic_tools { typedef nodelet_topic_tools::NodeletThrottle NodeletThrottleString; } -PLUGINLIB_DECLARE_CLASS (test_nodelet_topic_tools, NodeletThrottleString, test_nodelet_topic_tools::NodeletThrottleString, nodelet::Nodelet); +PLUGINLIB_EXPORT_CLASS(test_nodelet_topic_tools::NodeletThrottleString, nodelet::Nodelet) diff -Nru ros-nodelet-core-1.9.8/test_nodelet_topic_tools/test/test_lazy.py ros-nodelet-core-1.9.16/test_nodelet_topic_tools/test/test_lazy.py --- ros-nodelet-core-1.9.8/test_nodelet_topic_tools/test/test_lazy.py 2016-11-15 15:32:47.000000000 +0000 +++ ros-nodelet-core-1.9.16/test_nodelet_topic_tools/test/test_lazy.py 2018-11-03 12:16:03.000000000 +0000 @@ -85,6 +85,16 @@ else: raise ValueError('Not found topic: {}'.format(check_topic)) + sub.unregister() + rospy.sleep(1) # wait for disconnection + + # Check specified topics do not exist + _, subscriptions, _ = self.master.getSystemState() + for check_topic in check_connected_topics: + for topic, sub_node in subscriptions: + if topic == rospy.get_namespace() + check_topic: + raise ValueError('Found topic: {}'.format(check_topic)) + def _cb_test_subscriber_appears(self, msg): pass diff -Nru ros-nodelet-core-1.9.8/test_nodelet_topic_tools/test/test_nodelet_throttle.launch ros-nodelet-core-1.9.16/test_nodelet_topic_tools/test/test_nodelet_throttle.launch --- ros-nodelet-core-1.9.8/test_nodelet_topic_tools/test/test_nodelet_throttle.launch 2016-11-15 15:32:47.000000000 +0000 +++ ros-nodelet-core-1.9.16/test_nodelet_topic_tools/test/test_nodelet_throttle.launch 2018-11-03 12:16:03.000000000 +0000 @@ -1,11 +1,11 @@ - - \ No newline at end of file + diff -Nru ros-nodelet-core-1.9.8/test_nodelet_topic_tools/test/test_throttle.py ros-nodelet-core-1.9.16/test_nodelet_topic_tools/test/test_throttle.py --- ros-nodelet-core-1.9.8/test_nodelet_topic_tools/test/test_throttle.py 2016-11-15 15:32:47.000000000 +0000 +++ ros-nodelet-core-1.9.16/test_nodelet_topic_tools/test/test_throttle.py 2018-11-03 12:16:03.000000000 +0000 @@ -28,7 +28,7 @@ def test_nodelet_throttle(self): for i in range(0,10): self._pub.publish(String('hello, world')) - rospy.sleep(1.0) + rospy.sleep(1.0) self.assert_(self._msgs_rec > 0, "No messages received from nodelet throttle on topic \"string_out\"")