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

Jochen Sprickerhof jspricke at moszumanska.debian.org
Sat Sep 24 15:59:12 UTC 2016


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

jspricke pushed a commit to branch master
in repository ros-nodelet-core.

commit f49bda59d8bb68a96f021469be4226c7fe5b62d7
Author: Jochen Sprickerhof <git at jochen.sprickerhof.de>
Date:   Sat Sep 24 17:56:34 2016 +0200

    New upstream version 1.9.6
---
 nodelet/CHANGELOG.rst                              |   7 +-
 nodelet/package.xml                                |   2 +-
 nodelet_core/CHANGELOG.rst                         |   3 +
 nodelet_core/package.xml                           |   2 +-
 nodelet_topic_tools/CHANGELOG.rst                  |  12 +
 .../include/nodelet_topic_tools/nodelet_lazy.h     | 289 +++++++++++++++++++++
 nodelet_topic_tools/package.xml                    |   2 +-
 test_nodelet/CHANGELOG.rst                         |   3 +
 test_nodelet/package.xml                           |   2 +-
 test_nodelet_topic_tools/CHANGELOG.rst             |  12 +
 test_nodelet_topic_tools/CMakeLists.txt            |   3 +-
 test_nodelet_topic_tools/package.xml               |   2 +-
 .../test/empty_string_publisher.py                 |  56 ++++
 .../test/string_nodelet_lazy.cpp                   |  79 ++++++
 test_nodelet_topic_tools/test/test_lazy.py         |  94 +++++++
 .../test/test_nodelet_lazy.launch                  |  41 +++
 test_nodelet_topic_tools/test/test_nodelets.xml    |   5 +
 17 files changed, 606 insertions(+), 8 deletions(-)

diff --git a/nodelet/CHANGELOG.rst b/nodelet/CHANGELOG.rst
index 795cc65..ee735ca 100644
--- a/nodelet/CHANGELOG.rst
+++ b/nodelet/CHANGELOG.rst
@@ -2,6 +2,9 @@
 Changelog for package nodelet
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.9.6 (2016-09-20)
+------------------
+
 1.9.5 (2016-06-22)
 ------------------
 * more sane debugging messages
@@ -144,10 +147,10 @@ Changelog for package nodelet
 * ~Loader now stops callback manager threads before destroying the nodelets. Otherwise the worker threads could operate on nodelet data as/after it's destroyed.
 * Use ros::names::parentNamespace().
 * Cleaned scoped_ptr's out of ThreadInfo and updated its padding.
-* Made ThreadInfo::calling an atomic_count. This allows the manager thread to pick the queue with least work more accurately, and reduces contention b/c getSmallestQueue no longer needs to lock on queue_mutex_.
+* Made ThreadInfo::calling an atomic_count. This allows the manager thread to pick the queue with least work more accurately, and reduces contention b/c getSmallestQueue no longer needs to lock on ``queue_mutex_``.
 * Minor code cleanup and finer locking in managerThread().
 * Actually pad ThreadInfo to a multiple of 64 bytes. Previous expression was wrongly wrapped in sizeof().
-* Instead of thread_info_.resize(num_threads), push each ThreadInfo on individually. With resize(), all threads ended up sharing the same queue_mutex and queue_cond. Doesn't seem to be much of a performance win though.
+* Instead of ``thread_info_``.resize(num_threads), push each ThreadInfo on individually. With resize(), all threads ended up sharing the same queue_mutex and queue_cond. Doesn't seem to be much of a performance win though.
 * Added test instrumentation to CallbackQueueManager to track size of worker thread queues over time. Must be enabled at compilation time with -DNODELET_QUEUE_DEBUG.
 * nodelet patches for osx lion support from wjwwood
 * Added --no-bond option to nodelet loading to disable bonds.
diff --git a/nodelet/package.xml b/nodelet/package.xml
index 69a2c86..64ca637 100644
--- a/nodelet/package.xml
+++ b/nodelet/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>nodelet</name>
-  <version>1.9.5</version>
+  <version>1.9.6</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_core/CHANGELOG.rst b/nodelet_core/CHANGELOG.rst
index d63de40..d2493f2 100644
--- a/nodelet_core/CHANGELOG.rst
+++ b/nodelet_core/CHANGELOG.rst
@@ -2,6 +2,9 @@
 Changelog for package nodelet_core
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.9.6 (2016-09-20)
+------------------
+
 1.9.5 (2016-06-22)
 ------------------
 
diff --git a/nodelet_core/package.xml b/nodelet_core/package.xml
index 10c8de8..26bde92 100644
--- a/nodelet_core/package.xml
+++ b/nodelet_core/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>nodelet_core</name>
-  <version>1.9.5</version>
+  <version>1.9.6</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 bc720ef..98b07a1 100644
--- a/nodelet_topic_tools/CHANGELOG.rst
+++ b/nodelet_topic_tools/CHANGELOG.rst
@@ -2,6 +2,18 @@
 Changelog for package nodelet_topic_tools
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.9.6 (2016-09-20)
+------------------
+* Add NodeletLazy abstract class for lazy transport (`#45 <https://github.com/ros/nodelet_core/issues/45>`_)
+  * Add NodeletLazy abstract class for lazy transport
+  * Add test for NodeletLazy with checking its lazy-ness
+  * Fix ROS logging format supporting `ros/ros_comm#875 <https://github.com/ros/ros_comm/issues/875>`_
+  * Fix ever_subscribed\_ flag setting location
+  * Clearfy the comment describing advertise method
+  * Parameterize the duration to warn the no connection
+  User can disable this feature by setting -1 to the param.
+* Contributors: Kentaro Wada
+
 1.9.5 (2016-06-22)
 ------------------
 
diff --git a/nodelet_topic_tools/include/nodelet_topic_tools/nodelet_lazy.h b/nodelet_topic_tools/include/nodelet_topic_tools/nodelet_lazy.h
new file mode 100644
index 0000000..fccd942
--- /dev/null
+++ b/nodelet_topic_tools/include/nodelet_topic_tools/nodelet_lazy.h
@@ -0,0 +1,289 @@
+/*********************************************************************
+ * Software License Agreement (BSD License)
+ *
+ *  Copyright (c) 2014-2016, JSK Lab, University of Tokyo.
+ *  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/o2r other materials provided
+ *     with the distribution.
+ *   * Neither the name of the JSK Lab 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: Ryohei Ueda, Kentaro Wada <www.kentaro.wada at gmail.com>
+ */
+
+#ifndef NODELET_LAZY_H_
+#define NODELET_LAZY_H_
+
+#include <ros/ros.h>
+#include <nodelet/nodelet.h>
+#include <boost/thread.hpp>
+#include <string>
+#include <vector>
+
+namespace nodelet_topic_tools
+{
+
+/** @brief
+  * Enum to represent connection status.
+  */
+enum ConnectionStatus
+{
+  NOT_INITIALIZED,
+  NOT_SUBSCRIBED,
+  SUBSCRIBED
+};
+
+/** @brief
+  * Nodelet to automatically subscribe/unsubscribe
+  * topics according to subscription of advertised topics.
+  *
+  * It's important not to subscribe topic if no output is required.
+  *
+  * In order to watch advertised topics, need to use advertise template method.
+  * And create subscribers in subscribe() and shutdown them in unsubscribed().
+  *
+  */
+class NodeletLazy: public nodelet::Nodelet
+{
+public:
+  NodeletLazy() {}
+
+protected:
+  /** @brief
+    * Initialize nodehandles nh_ and pnh_. Subclass should call
+    * this method in its onInit method
+    */
+  virtual void onInit()
+  {
+    connection_status_ = NOT_SUBSCRIBED;
+    bool use_multithread;
+    ros::param::param<bool>("~use_multithread_callback", use_multithread, true);
+    if (use_multithread)
+    {
+      NODELET_DEBUG("Using multithread callback");
+      nh_.reset (new ros::NodeHandle(getMTNodeHandle()));
+      pnh_.reset (new ros::NodeHandle(getMTPrivateNodeHandle()));
+    }
+    else
+    {
+      NODELET_DEBUG("Using singlethread callback");
+      nh_.reset(new ros::NodeHandle(getNodeHandle()));
+      pnh_.reset(new ros::NodeHandle(getPrivateNodeHandle()));
+    }
+    // option to use lazy transport
+    pnh_->param("lazy", lazy_, true);
+    // option for logging about being subscribed
+    pnh_->param("verbose_connection", verbose_connection_, false);
+    if (!verbose_connection_)
+    {
+      nh_->param("verbose_connection", verbose_connection_, false);
+    }
+    // timer to warn when no connection in the specified seconds
+    ever_subscribed_ = false;
+    double duration_to_warn_no_connection;
+    pnh_->param("duration_to_warn_no_connection",
+                duration_to_warn_no_connection, 5.0);
+    if (duration_to_warn_no_connection > 0)
+    {
+      timer_ever_subscribed_ = nh_->createWallTimer(
+        ros::WallDuration(duration_to_warn_no_connection),
+        &NodeletLazy::warnNeverSubscribedCallback,
+        this,
+        /*oneshot=*/true);
+    }
+  }
+
+  /** @brief
+    * Post processing of initialization of nodelet.
+    * You need to call this method in order to use always_subscribe
+    * feature.
+    */
+  virtual void onInitPostProcess()
+  {
+    if (!lazy_)
+    {
+      boost::mutex::scoped_lock lock(connection_mutex_);
+      subscribe();
+      ever_subscribed_ = true;
+    }
+  }
+
+  /** @brief
+    * callback function which is called when new subscriber come
+    */
+  virtual void connectionCallback(const ros::SingleSubscriberPublisher& pub)
+  {
+    if (verbose_connection_)
+    {
+      NODELET_INFO("New connection or disconnection is detected");
+    }
+    if (lazy_)
+    {
+      boost::mutex::scoped_lock lock(connection_mutex_);
+      for (size_t i = 0; i < publishers_.size(); i++)
+      {
+        ros::Publisher pub = publishers_[i];
+        if (pub.getNumSubscribers() > 0)
+        {
+          if (connection_status_ != SUBSCRIBED)
+          {
+            if (verbose_connection_)
+            {
+              NODELET_INFO("Subscribe input topics");
+            }
+            subscribe();
+            connection_status_ = SUBSCRIBED;
+          }
+          if (!ever_subscribed_)
+          {
+            ever_subscribed_ = true;
+          }
+          return;
+        }
+      }
+      if (connection_status_ == SUBSCRIBED)
+      {
+        if (verbose_connection_)
+        {
+          NODELET_INFO("Unsubscribe input topics");
+        }
+        unsubscribe();
+        connection_status_ = NOT_SUBSCRIBED;
+      }
+    }
+  }
+
+  /** @brief
+    * callback function which is called when walltimer
+    * duration run out.
+    */
+  virtual void warnNeverSubscribedCallback(const ros::WallTimerEvent& event)
+  {
+    if (!ever_subscribed_)
+    {
+      NODELET_WARN("This node/nodelet subscribes topics only when subscribed.");
+    }
+  }
+
+
+  /** @brief
+    * This method is called when publisher is subscribed by other
+    * nodes.
+    * Set up subscribers in this method.
+    */
+  virtual void subscribe() = 0;
+
+  /** @brief
+    * This method is called when publisher is unsubscribed by other
+    * nodes.
+    * Shut down subscribers in this method.
+    */
+  virtual void unsubscribe() = 0;
+
+  /** @brief
+    * Update the list of Publishers created by this method.
+    * It automatically reads latch boolean parameter from nh and
+    * publish topic with appropriate latch parameter.
+    *
+    * @param nh NodeHandle.
+    * @param topic topic name to advertise.
+    * @param queue_size queue size for publisher.
+    * @param latch set true if latch topic publication.
+    * @return Publisher for the advertised topic.
+    */
+  template<class T> ros::Publisher
+  advertise(ros::NodeHandle& nh,
+            std::string topic, int queue_size, bool latch=false)
+  {
+    boost::mutex::scoped_lock lock(connection_mutex_);
+    ros::SubscriberStatusCallback connect_cb
+      = boost::bind(&NodeletLazy::connectionCallback, this, _1);
+    ros::SubscriberStatusCallback disconnect_cb
+      = boost::bind(&NodeletLazy::connectionCallback, this, _1);
+    ros::Publisher pub = nh.advertise<T>(topic, queue_size,
+                                          connect_cb,
+                                          disconnect_cb,
+                                          ros::VoidConstPtr(),
+                                          latch);
+    publishers_.push_back(pub);
+    return pub;
+  }
+
+  /** @brief
+    * mutex to call subscribe() and unsubscribe() in
+    * critical section.
+    */
+  boost::mutex connection_mutex_;
+
+  /** @brief
+    * Shared pointer to nodehandle.
+    */
+  boost::shared_ptr<ros::NodeHandle> nh_;
+
+  /** @brief
+    * Shared pointer to private nodehandle.
+    */
+  boost::shared_ptr<ros::NodeHandle> pnh_;
+
+  /** @brief
+    * List of watching publishers
+    */
+  std::vector<ros::Publisher> publishers_;
+
+  /** @brief
+    * WallTimer instance for warning about no connection.
+    */
+  ros::WallTimer timer_ever_subscribed_;
+
+  /** @brief
+    * A flag to check if the node has been ever subscribed
+    * or not.
+    */
+  bool ever_subscribed_;
+
+  /** @brief
+    * A flag to disable watching mechanism and always subscribe input
+    * topics. It can be specified via `~lazy` parameter.
+    */
+  bool lazy_;
+
+  /** @brief
+    * Status of connection
+    */
+  ConnectionStatus connection_status_;
+
+  /** @brief
+    * true if `~verbose_connection` or `verbose_connection` parameter is true.
+    */
+  bool verbose_connection_;
+
+private:
+};
+
+}  // namespace nodelet_topic_tools
+
+#endif  // NODELET_LAZY_H_
diff --git a/nodelet_topic_tools/package.xml b/nodelet_topic_tools/package.xml
index c5b3587..a865606 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.5</version>
+  <version>1.9.6</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 c649023..ad0b8f8 100644
--- a/test_nodelet/CHANGELOG.rst
+++ b/test_nodelet/CHANGELOG.rst
@@ -2,6 +2,9 @@
 Changelog for package test_nodelet
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.9.6 (2016-09-20)
+------------------
+
 1.9.5 (2016-06-22)
 ------------------
 
diff --git a/test_nodelet/package.xml b/test_nodelet/package.xml
index 88f1c6b..cbf8894 100644
--- a/test_nodelet/package.xml
+++ b/test_nodelet/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>test_nodelet</name>
-  <version>1.9.5</version>
+  <version>1.9.6</version>
   <description>
     A package for nodelet unit tests
   </description>
diff --git a/test_nodelet_topic_tools/CHANGELOG.rst b/test_nodelet_topic_tools/CHANGELOG.rst
index e7dee2c..9abb2d8 100644
--- a/test_nodelet_topic_tools/CHANGELOG.rst
+++ b/test_nodelet_topic_tools/CHANGELOG.rst
@@ -2,6 +2,18 @@
 Changelog for package test_nodelet_topic_tools
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.9.6 (2016-09-20)
+------------------
+* Add NodeletLazy abstract class for lazy transport (`#45 <https://github.com/ros/nodelet_core/issues/45>`_)
+  * Add NodeletLazy abstract class for lazy transport
+  * Add test for NodeletLazy with checking its lazy-ness
+  * Fix ROS logging format supporting `ros/ros_comm#875 <https://github.com/ros/ros_comm/issues/875>`_
+  * Fix ever_subscribed\_ flag setting location
+  * Clearfy the comment describing advertise method
+  * Parameterize the duration to warn the no connection
+  User can disable this feature by setting -1 to the param.
+* Contributors: Kentaro Wada
+
 1.9.5 (2016-06-22)
 ------------------
 * fix non-isolated build
diff --git a/test_nodelet_topic_tools/CMakeLists.txt b/test_nodelet_topic_tools/CMakeLists.txt
index 7d3a856..11ab1a8 100644
--- a/test_nodelet_topic_tools/CMakeLists.txt
+++ b/test_nodelet_topic_tools/CMakeLists.txt
@@ -10,9 +10,10 @@ catkin_package(
 
 if(CATKIN_ENABLE_TESTING)
   include_directories(SYSTEM ${catkin_INCLUDE_DIRS})
-  add_library(test_nodelet_topic_tools test/string_nodelet_throttle.cpp)
+  add_library(test_nodelet_topic_tools test/string_nodelet_lazy.cpp test/string_nodelet_throttle.cpp)
   target_link_libraries(test_nodelet_topic_tools ${catkin_LIBRARIES})
   add_dependencies(test_nodelet_topic_tools ${catkin_EXPORTED_TARGETS})
 
+  add_rostest(test/test_nodelet_lazy.launch)
   add_rostest(test/test_nodelet_throttle.launch)
 endif()
diff --git a/test_nodelet_topic_tools/package.xml b/test_nodelet_topic_tools/package.xml
index 0d58fdf..f96ebf0 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.5</version>
+  <version>1.9.6</version>
   <description>
     A package for nodelet_topic_tools unit tests.
   </description>
diff --git a/test_nodelet_topic_tools/test/empty_string_publisher.py b/test_nodelet_topic_tools/test/empty_string_publisher.py
new file mode 100755
index 0000000..527e749
--- /dev/null
+++ b/test_nodelet_topic_tools/test/empty_string_publisher.py
@@ -0,0 +1,56 @@
+#!/usr/bin/env python
+###############################################################################
+# Software License Agreement (BSD License)
+#
+#  Copyright (c) 2016, JSK Lab, University of Tokyo.
+#  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/o2r other materials provided
+#     with the distribution.
+#   * Neither the name of the JSK Lab 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__ = 'Kentaro Wada <www.kentaro.wada at gmail.com>'
+
+import rospy
+from std_msgs.msg import String
+
+
+class EmptyStringPublisher(object):
+
+    def __init__(self):
+        self.pub = rospy.Publisher('~output', String, queue_size=1)
+        self.timer_pub = rospy.Timer(
+            rospy.Duration(0.1), self.publish_callback)
+
+    def publish_callback(self, event):
+        self.pub.publish(String())
+
+
+if __name__ == '__main__':
+    rospy.init_node('empty_string_publisher')
+    EmptyStringPublisher()
+    rospy.spin()
diff --git a/test_nodelet_topic_tools/test/string_nodelet_lazy.cpp b/test_nodelet_topic_tools/test/string_nodelet_lazy.cpp
new file mode 100644
index 0000000..d5152f6
--- /dev/null
+++ b/test_nodelet_topic_tools/test/string_nodelet_lazy.cpp
@@ -0,0 +1,79 @@
+/*********************************************************************
+ * Software License Agreement (BSD License)
+ *
+ *  Copyright (c) 2016, JSK Lab, University of Tokyo.
+ *  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/o2r other materials provided
+ *     with the distribution.
+ *   * Neither the name of the JSK Lab 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: Kentaro Wada <www.kentaro.wada at gmail.com>
+ */
+
+#include <nodelet_topic_tools/nodelet_lazy.h>
+#include <std_msgs/String.h>
+
+namespace test_nodelet_topic_tools
+{
+
+class NodeletLazyString: public nodelet_topic_tools::NodeletLazy
+{
+public:
+protected:
+  virtual void onInit()
+  {
+    nodelet_topic_tools::NodeletLazy::onInit();
+    pub_ = advertise<std_msgs::String>(*pnh_, "output", 1);
+    onInitPostProcess();
+  }
+
+  virtual void subscribe()
+  {
+    sub_ = pnh_->subscribe("input", 1, &NodeletLazyString::callback, this);
+  }
+
+  virtual void unsubscribe()
+  {
+    sub_.shutdown();
+  }
+
+  virtual void callback(const std_msgs::String::ConstPtr& msg)
+  {
+    pub_.publish(msg);
+  }
+
+  ros::Publisher pub_;
+  ros::Subscriber sub_;
+
+private:
+};
+
+}  // namespace test_nodelet_topic_tools
+
+#include <pluginlib/class_list_macros.h>
+PLUGINLIB_EXPORT_CLASS(test_nodelet_topic_tools::NodeletLazyString, nodelet::Nodelet);
diff --git a/test_nodelet_topic_tools/test/test_lazy.py b/test_nodelet_topic_tools/test/test_lazy.py
new file mode 100755
index 0000000..029b350
--- /dev/null
+++ b/test_nodelet_topic_tools/test/test_lazy.py
@@ -0,0 +1,94 @@
+#!/usr/bin/env python
+###############################################################################
+# Software License Agreement (BSD License)
+#
+#  Copyright (c) 2016, JSK Lab, University of Tokyo.
+#  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/o2r other materials provided
+#     with the distribution.
+#   * Neither the name of the JSK Lab 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__ = 'Kentaro Wada <www.kentaro.wada at gmail.com>'
+
+import os
+import sys
+
+import unittest
+
+import rosgraph
+import rospy
+import rosmsg
+import roslib
+
+
+PKG = 'test_nodelet_topic_tools'
+NAME = 'test_lazy'
+
+
+class TestConnection(unittest.TestCase):
+
+    def __init__(self, *args):
+        super(TestConnection, self).__init__(*args)
+        rospy.init_node(NAME)
+        self.master = rosgraph.Master(NAME)
+
+    def test_no_subscribers(self):
+        check_connected_topics = rospy.get_param('~check_connected_topics')
+        # Check assumed topics are not there
+        _, 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 test_subscriber_appears(self):
+        topic_type = rospy.get_param('~input_topic_type')
+        check_connected_topics = rospy.get_param('~check_connected_topics')
+        wait_time = rospy.get_param('~wait_for_connection', 0)
+        msg_class = roslib.message.get_message_class(topic_type)
+        # Subscribe topic and bond connection
+        sub = rospy.Subscriber('~input', msg_class,
+                               self._cb_test_subscriber_appears)
+        print('Waiting for connection for {} sec.'.format(wait_time))
+        rospy.sleep(wait_time)
+        # Check assumed topics are there
+        _, subscriptions, _ = self.master.getSystemState()
+        for check_topic in check_connected_topics:
+            for topic, sub_node in subscriptions:
+                if topic == rospy.get_namespace() + check_topic:
+                    break
+            else:
+                raise ValueError('Not found topic: {}'.format(check_topic))
+
+    def _cb_test_subscriber_appears(self, msg):
+        pass
+
+
+if __name__ == "__main__":
+    import rostest
+    rostest.rosrun(PKG, NAME, TestConnection)
diff --git a/test_nodelet_topic_tools/test/test_nodelet_lazy.launch b/test_nodelet_topic_tools/test/test_nodelet_lazy.launch
new file mode 100644
index 0000000..9649990
--- /dev/null
+++ b/test_nodelet_topic_tools/test/test_nodelet_lazy.launch
@@ -0,0 +1,41 @@
+<launch>
+
+  <node name="empty_string_publisher"
+        pkg="test_nodelet_topic_tools" type="empty_string_publisher.py">
+    <remap from="~output" to="input" />
+  </node>
+
+  <param name="verbose_connection" value="true" />
+
+  <node name="string_nodelet_lazy_0"
+        pkg="nodelet" type="nodelet"
+        args="standalone test_nodelet_topic_tools/NodeletLazyString"
+        output="screen">
+    <remap from="~input"  to="input"/>
+  </node>
+  <node name="string_nodelet_lazy_1"
+        pkg="nodelet" type="nodelet"
+        args="standalone test_nodelet_topic_tools/NodeletLazyString"
+        output="screen">
+    <remap from="~input"  to="string_nodelet_lazy_0/output"/>
+  </node>
+  <node name="string_nodelet_lazy_2"
+        pkg="nodelet" type="nodelet"
+        args="standalone test_nodelet_topic_tools/NodeletLazyString"
+        output="screen">
+    <remap from="~input"  to="string_nodelet_lazy_1/output"/>
+  </node>
+
+  <test test-name="test_lazy"
+        name="test_lazy"
+        pkg="test_nodelet_topic_tools" type="test_lazy.py"
+        retry="3">
+    <rosparam>
+      input_topic_type: std_msgs/String
+      check_connected_topics: [string_nodelet_lazy_0/output, string_nodelet_lazy_1/output]
+      wait_for_connection: 3
+    </rosparam>
+    <remap from="~input" to="string_nodelet_lazy_2/output" />
+  </test>
+
+</launch>
diff --git a/test_nodelet_topic_tools/test/test_nodelets.xml b/test_nodelet_topic_tools/test/test_nodelets.xml
index 7ab2dee..aacb21f 100644
--- a/test_nodelet_topic_tools/test/test_nodelets.xml
+++ b/test_nodelet_topic_tools/test/test_nodelets.xml
@@ -4,4 +4,9 @@
       Throttle strings in nodelet (testing only).
     </description>
   </class>
+  <class name="test_nodelet_topic_tools/NodeletLazyString" type="test_nodelet_topic_tools::NodeletLazyString" base_class_type="nodelet::Nodelet">
+    <description>
+      Lazy transport strings in nodelet (testing only).
+    </description>
+  </class>
 </library>

-- 
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