[ros-vision-opencv] 01/03: Revert "Merge tag 'upstream/1.12.0+ds'"

Jochen Sprickerhof jspricke at moszumanska.debian.org
Tue Aug 30 21:37:04 UTC 2016


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

jspricke pushed a commit to annotated tag debian/1.11.11+ds-4
in repository ros-vision-opencv.

commit df0cb6c91e7935123d6ca6a8f8b1fe311ffd30b3
Author: Jochen Sprickerhof <git at jochen.sprickerhof.de>
Date:   Tue Aug 30 23:03:03 2016 +0200

    Revert "Merge tag 'upstream/1.12.0+ds'"
    
    This reverts commit 5aca9a423816a286de6ca208ff82ec4950f22af8, reversing
    changes made to 79b3e7af4ad7aed8cccb8b09e8c52d4544fc0954.
---
 .travis.yml                                        |   9 +-
 cv_bridge/CHANGELOG.rst                            |  14 -
 cv_bridge/package.xml                              |   8 +-
 cv_bridge/python/cv_bridge/core.py                 |   8 +-
 image_geometry/CHANGELOG.rst                       |  10 -
 image_geometry/package.xml                         |   8 +-
 image_geometry/src/pinhole_camera_model.cpp        |  11 +-
 image_geometry/test/utest.cpp                      |  91 ------
 opencv_apps/CHANGELOG.rst                          |  17 --
 opencv_apps/CMakeLists.txt                         |  14 +-
 opencv_apps/include/opencv_apps/nodelet.h          | 318 ---------------------
 opencv_apps/package.xml                            |   4 +-
 opencv_apps/src/nodelet/camshift_nodelet.cpp       |  75 +++--
 .../src/nodelet/contour_moments_nodelet.cpp        |  69 ++++-
 opencv_apps/src/nodelet/convex_hull_nodelet.cpp    |  68 ++++-
 opencv_apps/src/nodelet/edge_detection_nodelet.cpp |  68 ++++-
 opencv_apps/src/nodelet/face_detection_nodelet.cpp |  75 +++--
 opencv_apps/src/nodelet/fback_flow_nodelet.cpp     |  70 ++++-
 opencv_apps/src/nodelet/find_contours_nodelet.cpp  |  70 ++++-
 .../src/nodelet/general_contours_nodelet.cpp       |  70 ++++-
 .../src/nodelet/goodfeature_track_nodelet.cpp      |  68 ++++-
 opencv_apps/src/nodelet/hough_circles_nodelet.cpp  |  70 ++++-
 opencv_apps/src/nodelet/hough_lines_nodelet.cpp    |  68 ++++-
 opencv_apps/src/nodelet/lk_flow_nodelet.cpp        |  75 +++--
 opencv_apps/src/nodelet/nodelet.cpp                | 184 ------------
 opencv_apps/src/nodelet/people_detect_nodelet.cpp  |  72 ++++-
 opencv_apps/src/nodelet/phase_corr_nodelet.cpp     |  70 ++++-
 .../src/nodelet/segment_objects_nodelet.cpp        |  72 ++++-
 opencv_apps/src/nodelet/simple_flow_nodelet.cpp    |  67 ++++-
 .../src/nodelet/watershed_segmentation_nodelet.cpp |  71 ++++-
 opencv_apps/test/test-hough_lines.test             |   4 +-
 opencv_apps/test/test-people_detect.test           |   2 +-
 opencv_apps/test/test-simple_flow.test             |   4 +-
 opencv_tests/CHANGELOG.rst                         |   6 -
 opencv_tests/package.xml                           |   2 +-
 vision_opencv/CHANGELOG.rst                        |   8 -
 vision_opencv/package.xml                          |   4 +-
 37 files changed, 991 insertions(+), 933 deletions(-)

diff --git a/.travis.yml b/.travis.yml
index 34eca30..83dfb40 100644
--- a/.travis.yml
+++ b/.travis.yml
@@ -2,8 +2,10 @@ sudo: required
 dist: trusty
 language: generic
 env:
-  - ROS_DISTRO=indigo
-  - ROS_DISTRO=jade
+  - OPENCV_VERSION=2 ROS_DISTRO=indigo
+  - OPENCV_VERSION=3 ROS_DISTRO=indigo
+  - OPENCV_VERSION=2 ROS_DISTRO=jade
+  - OPENCV_VERSION=3 ROS_DISTRO=jade
 # Install system dependencies, namely ROS.
 before_install:
   # Define some config vars.
@@ -32,6 +34,8 @@ install:
   - cd ~/catkin_ws/src
   - ln -s $CI_SOURCE_PATH . # Link the repo we are testing to the new workspace
 
+  - if [ $OPENCV_VERSION == 3 ]; then  sed -i 's at libopencv-dev@opencv3@' $REPOSITORY_NAME/*/package.xml ; fi
+
 # Install all dependencies, using wstool and rosdep.
 # wstool looks for a ROSINSTALL_FILE defined in before_install.
 before_script:
@@ -39,6 +43,7 @@ before_script:
   - cd ~/catkin_ws/src
   - wstool init
   - if [[ -f $ROSINSTALL_FILE ]] ; then wstool merge $ROSINSTALL_FILE ; fi
+  - if [ $OPENCV_VERSION == 3 ]; then wstool set -y image_pipeline --git https://github.com/ros-perception/image_pipeline; fi # need to recompile image_proc
   - wstool up
 
   # package depdencies: install using rosdep.
diff --git a/cv_bridge/CHANGELOG.rst b/cv_bridge/CHANGELOG.rst
index 48b6021..3805a63 100644
--- a/cv_bridge/CHANGELOG.rst
+++ b/cv_bridge/CHANGELOG.rst
@@ -2,20 +2,6 @@
 Changelog for package cv_bridge
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
-1.12.0 (2016-03-18)
--------------------
-* depend on OpenCV3 only
-* Contributors: Vincent Rabaud
-
-1.11.12 (2016-03-10)
---------------------
-* Fix my typo
-* Remove another eval
-  Because `cvtype2_to_dtype_with_channels('8UCimport os; os.system("rm -rf /")')` should never have a chance of happening.
-* Remove eval, and other fixes
-  Also, extend from object, so as not to get a python 2.2-style class, and use the new-style raise statement
-* Contributors: Eric Wieser
-
 1.11.11 (2016-01-31)
 --------------------
 * clean up the doc files
diff --git a/cv_bridge/package.xml b/cv_bridge/package.xml
index 5465c70..a5df57c 100644
--- a/cv_bridge/package.xml
+++ b/cv_bridge/package.xml
@@ -1,6 +1,6 @@
 <package format="2">
   <name>cv_bridge</name>
-  <version>1.12.0</version>
+  <version>1.11.11</version>
   <description>
     This contains CvBridge, which converts between ROS
     Image messages and OpenCV images.
@@ -20,14 +20,16 @@
   <buildtool_depend version_gte="0.5.68">catkin</buildtool_depend>
 
   <build_depend>boost</build_depend>
-  <build_depend>opencv3</build_depend>
+  <build_depend>libopencv-dev</build_depend>
   <build_depend>python</build_depend>
+  <build_depend>python-opencv</build_depend>
   <build_depend>rosconsole</build_depend>
   <build_depend>sensor_msgs</build_depend>
 
   <exec_depend>boost</exec_depend>
-  <exec_depend>opencv3</exec_depend>
+  <exec_depend>libopencv-dev</exec_depend>
   <exec_depend>python</exec_depend>
+  <exec_depend>python-opencv</exec_depend>
   <exec_depend>rosconsole</exec_depend>
   <build_export_depend>sensor_msgs</build_export_depend>
 
diff --git a/cv_bridge/python/cv_bridge/core.py b/cv_bridge/python/cv_bridge/core.py
index af72dab..9549c9c 100644
--- a/cv_bridge/python/cv_bridge/core.py
+++ b/cv_bridge/python/cv_bridge/core.py
@@ -38,7 +38,7 @@ class CvBridgeError(TypeError):
     """
     pass
 
-class CvBridge(object):
+class CvBridge:
     """
     The CvBridge is an object that converts between OpenCV Images and ROS Image messages.
 
@@ -64,7 +64,7 @@ class CvBridge(object):
         for t in ["8U", "8S", "16U", "16S", "32S", "32F", "64F" ]:
             for c in [1,2,3,4]:
                 nm = "%sC%d" % (t, c)
-                self.cvtype_to_name[getattr(cv2, "CV_%s" % nm)] = nm
+                self.cvtype_to_name[eval("cv2.CV_%s" % nm)] = nm
 
         self.numpy_type_to_cvtype = {'uint8':'8U', 'int8':'8S', 'uint16':'16U',
                                         'int16':'16S', 'int32':'32S', 'float32':'32F',
@@ -77,7 +77,7 @@ class CvBridge(object):
     def cvtype2_to_dtype_with_channels(self, cvtype):
         import re
         vals = re.split('(.+)C(.+)', self.cvtype_to_name[cvtype])
-        return self.numpy_type_to_cvtype[vals[1]], int(vals[2])
+        return self.numpy_type_to_cvtype[vals[1]], eval(vals[2])
 
     def encoding_to_cvtype2(self, encoding):
         from cv_bridge.boost.cv_bridge_boost import getCvType
@@ -167,7 +167,7 @@ class CvBridge(object):
             img_msg.encoding = encoding
             # Verify that the supplied encoding is compatible with the type of the OpenCV image
             if self.cvtype_to_name[self.encoding_to_cvtype2(encoding)] != cv_type:
-                raise CvBridgeError("encoding specified as %s, but image has incompatible type %s" % (encoding, cv_type))
+              raise CvBridgeError, "encoding specified as %s, but image has incompatible type %s" % (encoding, cv_type)
         img_msg.data = cvim.tostring()
         img_msg.step = len(img_msg.data) / img_msg.height
         return img_msg
diff --git a/image_geometry/CHANGELOG.rst b/image_geometry/CHANGELOG.rst
index 213432e..b0158d5 100644
--- a/image_geometry/CHANGELOG.rst
+++ b/image_geometry/CHANGELOG.rst
@@ -2,16 +2,6 @@
 Changelog for package image_geometry
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
-1.12.0 (2016-03-18)
--------------------
-* depend on OpenCV3 only
-* Contributors: Vincent Rabaud
-
-1.11.12 (2016-03-10)
---------------------
-* issue `#117 <https://github.com/ros-perception/vision_opencv/issues/117>`_ pull request `#118 <https://github.com/ros-perception/vision_opencv/issues/118>`_ check all distortion coefficients to see if rectification ought to be done
-* Contributors: Lucas Walter
-
 1.11.11 (2016-01-31)
 --------------------
 * clean up the doc files
diff --git a/image_geometry/package.xml b/image_geometry/package.xml
index 7e5ef4d..f484464 100644
--- a/image_geometry/package.xml
+++ b/image_geometry/package.xml
@@ -1,6 +1,6 @@
 <package format="2">
   <name>image_geometry</name>
-  <version>1.12.0</version>
+  <version>1.11.11</version>
   <description>
     `image_geometry` contains C++ and Python libraries for interpreting images
     geometrically. It interfaces the calibration parameters in sensor_msgs/CameraInfo
@@ -18,10 +18,12 @@
 
   <buildtool_depend version_gte="0.5.68">catkin</buildtool_depend>
 
-  <build_depend>opencv3</build_depend>
+  <build_depend>libopencv-dev</build_depend>
+  <build_depend>python-opencv</build_depend>
   <build_depend>sensor_msgs</build_depend>
 
-  <exec_depend>opencv3</exec_depend>
+  <exec_depend>libopencv-dev</exec_depend>
+  <exec_depend>python-opencv</exec_depend>
   <build_export_depend>sensor_msgs</build_export_depend>
 
   <doc_depend>dvipng</doc_depend>
diff --git a/image_geometry/src/pinhole_camera_model.cpp b/image_geometry/src/pinhole_camera_model.cpp
index d2273f6..ea1f940 100644
--- a/image_geometry/src/pinhole_camera_model.cpp
+++ b/image_geometry/src/pinhole_camera_model.cpp
@@ -127,16 +127,7 @@ bool PinholeCameraModel::fromCameraInfo(const sensor_msgs::CameraInfo& msg)
   // Figure out how to handle the distortion
   if (cam_info_.distortion_model == sensor_msgs::distortion_models::PLUMB_BOB ||
       cam_info_.distortion_model == sensor_msgs::distortion_models::RATIONAL_POLYNOMIAL) {
-    // If any distortion coefficient is non-zero, then need to apply the distortion
-    cache_->distortion_state = NONE;
-    for (size_t i = 0; i < cam_info_.D.size(); ++i)
-    {
-      if (cam_info_.D[i] != 0)
-      {
-        cache_->distortion_state = CALIBRATED;
-        break;
-      }
-    }
+    cache_->distortion_state = (cam_info_.D.size() == 0 || (cam_info_.D[0] == 0.0)) ? NONE : CALIBRATED;
   }
   else
     cache_->distortion_state = UNKNOWN;
diff --git a/image_geometry/test/utest.cpp b/image_geometry/test/utest.cpp
index 67e2e4b..ad58896 100644
--- a/image_geometry/test/utest.cpp
+++ b/image_geometry/test/utest.cpp
@@ -161,97 +161,6 @@ TEST_F(PinholeTest, initialization)
     EXPECT_EQ(camera.projectionMatrix().cols, 4);
 }
 
-TEST_F(PinholeTest, rectifyIfCalibrated)
-{
-  /// @todo use forward distortion for a better test
-  // Ideally this test would have two images stored on disk
-  // one which is distorted and the other which is rectified,
-  // and then rectification would take place here and the output
-  // image compared to the one on disk (which would mean if
-  // the distortion coefficients above can't change once paired with
-  // an image).
-
-  // Later could incorporate distort code
-  // (https://github.com/lucasw/vimjay/blob/master/src/standalone/distort_image.cpp)
-  // to take any image distort it, then undistort with rectifyImage,
-  // and given the distortion coefficients are consistent the input image
-  // and final output image should be mostly the same (though some
-  // interpolation error
-  // creeps in), except for outside a masked region where information was lost.
-  // The masked region can be generated with a pure white image that
-  // goes through the same process (if it comes out completely black
-  // then the distortion parameters are problematic).
-
-  // For now generate an image and pass the test simply if
-  // the rectified image does not match the distorted image.
-  // Then zero out the first distortion coefficient and run
-  // the test again.
-  // Then zero out all the distortion coefficients and test
-  // that the output image is the same as the input.
-  cv::Mat distorted_image(cv::Size(cam_info_.width, cam_info_.height), CV_8UC3);
-
-  // draw a grid
-  const cv::Scalar color = cv::Scalar(255, 255, 255);
-  // draw the lines thick so the proportion of error due to
-  // interpolation is reduced
-  const int thickness = 7;
-  const int type = 8;
-  for (size_t y = 0; y <= cam_info_.height; y += cam_info_.height/10)
-  {
-    cv::line(distorted_image,
-             cv::Point(0, y), cv::Point(cam_info_.width, y),
-             color, type, thickness);
-  }
-  for (size_t x = 0; x <= cam_info_.width; x += cam_info_.width/10)
-  {
-    // draw the lines thick so the prorportion of interpolation error is reduced
-    cv::line(distorted_image,
-             cv::Point(x, 0), cv::Point(x, cam_info_.height),
-             color, type, thickness);
-  }
-
-  cv::Mat rectified_image;
-  // Just making this number up, maybe ought to be larger
-  // since a completely different image would be on the order of
-  // width * height * 255 = 78e6
-  const double diff_threshold = 10000.0;
-  double error;
-
-  // Test that rectified image is sufficiently different
-  // using default distortion
-  model_.rectifyImage(distorted_image, rectified_image);
-  error = cv::norm(distorted_image, rectified_image, cv::NORM_L1);
-  // Just making this number up, maybe ought to be larger
-  EXPECT_GT(error, diff_threshold);
-
-  // Test that rectified image is sufficiently different
-  // using default distortion but with first element zeroed
-  // out.
-  sensor_msgs::CameraInfo cam_info_2 = cam_info_;
-  cam_info_2.D[0] = 0.0;
-  model_.fromCameraInfo(cam_info_2);
-  model_.rectifyImage(distorted_image, rectified_image);
-  error = cv::norm(distorted_image, rectified_image, cv::NORM_L1);
-  EXPECT_GT(error, diff_threshold);
-
-  // Test that rectified image is the same using zero distortion
-  cam_info_2.D.assign(cam_info_2.D.size(), 0);
-  model_.fromCameraInfo(cam_info_2);
-  model_.rectifyImage(distorted_image, rectified_image);
-  error = cv::norm(distorted_image, rectified_image, cv::NORM_L1);
-  EXPECT_EQ(error, 0);
-
-  // Test that rectified image is the same using empty distortion
-  cam_info_2.D.clear();
-  model_.fromCameraInfo(cam_info_2);
-  model_.rectifyImage(distorted_image, rectified_image);
-  error = cv::norm(distorted_image, rectified_image, cv::NORM_L1);
-  EXPECT_EQ(error, 0);
-
-  // restore original distortion
-  model_.fromCameraInfo(cam_info_);
-}
-
 int main(int argc, char** argv)
 {
   testing::InitGoogleTest(&argc, argv);
diff --git a/opencv_apps/CHANGELOG.rst b/opencv_apps/CHANGELOG.rst
index d5ca927..dda30f2 100644
--- a/opencv_apps/CHANGELOG.rst
+++ b/opencv_apps/CHANGELOG.rst
@@ -2,23 +2,6 @@
 Changelog for package opencv_apps
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
-1.12.0 (2016-03-18)
--------------------
-* geometry_msgs doesn't get used by opencv_apps, but std_msgs does.
-* Contributors: Lucas Walter
-
-1.11.12 (2016-03-10)
---------------------
-* relax test condition
-* fix test hz to 5 hz, tested on core i7 3.2G
-* Refactor opencv_apps to remove duplicated codes to handle connection of
-  topics.
-  1. Add opencv_apps::Nodelet class to handle connection and disconnection of
-  topics.
-  2. Update nodelets of opencv_apps to inhereit opencv_apps::Nodelet class
-  to remove duplicated codes.
-* Contributors: Kei Okada, Ryohei Ueda
-
 1.11.11 (2016-01-31)
 --------------------
 * check if opencv_contrib is available
diff --git a/opencv_apps/CMakeLists.txt b/opencv_apps/CMakeLists.txt
index 159573f..79865da 100644
--- a/opencv_apps/CMakeLists.txt
+++ b/opencv_apps/CMakeLists.txt
@@ -66,16 +66,12 @@ add_message_files(
 ## Generate added messages and services with any dependencies listed here
 generate_messages(
   DEPENDENCIES
-  std_msgs
+  geometry_msgs
 )
 
-catkin_package(CATKIN_DEPENDS std_msgs
-#                DEPENDS OpenCV
-               INCLUDE_DIRS include
-               LIBRARIES ${PROJECT_NAME}
-)
+catkin_package()
 
-include_directories(include ${catkin_INCLUDE_DIRS} ${OpenCV_INCLUDE_DIRS})
+include_directories( ${catkin_INCLUDE_DIRS} ${OpenCV_INCLUDE_DIRS})
 
 ## Declare a cpp library
 if(OPENCV_HAVE_OPTFLOW)
@@ -83,7 +79,6 @@ if(OPENCV_HAVE_OPTFLOW)
 endif()
 
 add_library(${PROJECT_NAME} SHARED
-  src/nodelet/nodelet.cpp
   # https://github.com/Itseez/opencv/blob/2.4/samples/cpp/tutorial_code
   # ImgTrans
   src/nodelet/edge_detection_nodelet.cpp
@@ -298,8 +293,7 @@ add_executable(watershed_segmentation_exe src/node/watershed_segmentation.cpp)
 SET_TARGET_PROPERTIES(watershed_segmentation_exe PROPERTIES OUTPUT_NAME watershed_segmentation)
 target_link_libraries(watershed_segmentation_exe ${catkin_LIBRARIES} ${OpenCV_LIBRARIES})
 
-install(DIRECTORY include/${PROJECT_NAME}/
-  DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION})
+
 install(TARGETS edge_detection_exe hough_lines_exe hough_circles_exe face_detection_exe goodfeature_track_exe
   camshift_exe simple_example_exe simple_compressed_example_exe fback_flow_exe lk_flow_exe people_detect_exe phase_corr_exe segment_objects_exe watershed_segmentation_exe
         DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
diff --git a/opencv_apps/include/opencv_apps/nodelet.h b/opencv_apps/include/opencv_apps/nodelet.h
deleted file mode 100644
index 5418806..0000000
--- a/opencv_apps/include/opencv_apps/nodelet.h
+++ /dev/null
@@ -1,318 +0,0 @@
-/*********************************************************************
-* Software License Agreement (BSD License)
-*
-*  Copyright (c) 2016, Ryohei Ueda.
-*  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 the Kei Okada 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.
-*********************************************************************/
-
-#ifndef OPENCV_APPS_NODELET_H_
-#define OPENCV_APPS_NODELET_H_
-
-#include <ros/ros.h>
-#include <nodelet/nodelet.h>
-#include <boost/thread.hpp>
-#include <image_transport/image_transport.h>
-
-namespace opencv_apps
-{
-  /** @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 Nodelet: public nodelet::Nodelet
-  {
-  public:
-    Nodelet(): subscribed_(false) { }
-  protected:
-    
-    /** @brief
-     * Initialize nodehandles nh_ and pnh_. Subclass should call
-     * this method in its onInit method
-     */
-    virtual void onInit();
-
-
-    /** @brief
-     * Post processing of initialization of nodelet.
-     * You need to call this method in order to use always_subscribe
-     * feature.
-     */
-    virtual void onInitPostProcess();
-    
-    /** @brief
-     * callback function which is called when new subscriber come
-     */
-    virtual void connectionCallback(const ros::SingleSubscriberPublisher& pub);
-
-    /** @brief
-     * callback function which is called when new subscriber come for image
-     * publisher
-     */
-    virtual void imageConnectionCallback(
-      const image_transport::SingleSubscriberPublisher& pub);
-
-    /** @brief
-     * callback function which is called when new subscriber come for camera
-     * image publisher
-     */
-    virtual void cameraConnectionCallback(
-      const image_transport::SingleSubscriberPublisher& pub);
-    
-    /** @brief
-     * callback function which is called when new subscriber come for
-     * camera info publisher
-     */
-    virtual void cameraInfoConnectionCallback(
-      const ros::SingleSubscriberPublisher& pub);
-    
-    /** @brief
-     * callback function which is called when new subscriber come for camera
-     * image publisher or camera info publisher.
-     * This function is called from cameraConnectionCallback
-     * or cameraInfoConnectionCallback.
-     */
-    virtual void cameraConnectionBaseCallback();
-
-    /** @brief
-     * callback function which is called when walltimer
-     * duration run out.
-     */
-    virtual void warnNeverSubscribedCallback(const ros::WallTimerEvent& event);
-
-    /** @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
-     * Advertise a topic and watch the publisher. Publishers which are
-     * 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)
-    {
-      boost::mutex::scoped_lock lock(connection_mutex_);
-      ros::SubscriberStatusCallback connect_cb
-        = boost::bind(&Nodelet::connectionCallback, this, _1);
-      ros::SubscriberStatusCallback disconnect_cb
-        = boost::bind(&Nodelet::connectionCallback, this, _1);
-      bool latch;
-      nh.param("latch", latch, false);
-      ros::Publisher ret = nh.advertise<T>(topic, queue_size,
-                                           connect_cb,
-                                           disconnect_cb,
-                                           ros::VoidConstPtr(),
-                                           latch);
-      publishers_.push_back(ret);
-      
-      return ret;
-    }
-
-    /** @brief
-     * Advertise an image topic and watch the publisher. Publishers which are
-     * created by this method.
-     * It automatically reads latch boolean parameter from nh and it 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.
-     */
-    image_transport::Publisher
-    advertiseImage(ros::NodeHandle& nh,
-                   const std::string& topic,
-                   int queue_size)
-    {
-      boost::mutex::scoped_lock lock(connection_mutex_);
-      image_transport::SubscriberStatusCallback connect_cb
-        = boost::bind(&Nodelet::imageConnectionCallback,
-                      this, _1);
-      image_transport::SubscriberStatusCallback disconnect_cb
-        = boost::bind(&Nodelet::imageConnectionCallback,
-                      this, _1);
-      bool latch;
-      nh.param("latch", latch, false);
-      image_transport::Publisher pub
-        = image_transport::ImageTransport(nh).advertise(
-          topic, 1,
-          connect_cb, disconnect_cb,
-          ros::VoidPtr(), latch);
-      image_publishers_.push_back(pub);
-      return pub;
-    }
-
-    /** @brief
-     * Advertise an image topic camera info topic and watch the publisher.
-     * Publishers which are
-     * created by this method.
-     * It automatically reads latch boolean parameter from nh and it 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.
-     */
-    image_transport::CameraPublisher
-    advertiseCamera(ros::NodeHandle& nh,
-                    const std::string& topic,
-                    int queue_size)
-    {
-      boost::mutex::scoped_lock lock(connection_mutex_);
-      image_transport::SubscriberStatusCallback connect_cb
-        = boost::bind(&Nodelet::cameraConnectionCallback,
-                      this, _1);
-      image_transport::SubscriberStatusCallback disconnect_cb
-        = boost::bind(&Nodelet::cameraConnectionCallback,
-                      this, _1);
-      ros::SubscriberStatusCallback info_connect_cb
-        = boost::bind(&Nodelet::cameraInfoConnectionCallback,
-                      this, _1);
-      ros::SubscriberStatusCallback info_disconnect_cb
-        = boost::bind(&Nodelet::cameraInfoConnectionCallback,
-                      this, _1);
-      bool latch;
-      nh.param("latch", latch, false);
-      image_transport::CameraPublisher
-        pub = image_transport::ImageTransport(nh).advertiseCamera(topic, 1,
-                                                                  connect_cb, disconnect_cb,
-                                                                  info_connect_cb, info_disconnect_cb,
-                                                                  ros::VoidPtr(),
-                                                                  latch);
-      camera_publishers_.push_back(pub);
-      return pub;
-    }
-    
-    /** @brief
-     * mutex to call subscribe() and unsubscribe() in
-     * critical section.
-     */
-    boost::mutex connection_mutex_;
-    
-    /** @brief
-     * List of watching publishers
-     */
-    std::vector<ros::Publisher> publishers_;
-
-    /** @brief
-     * List of watching image publishers
-     */
-    std::vector<image_transport::Publisher> image_publishers_;
-
-    /** @brief
-     * List of watching camera publishers
-     */
-    std::vector<image_transport::CameraPublisher> camera_publishers_;
-
-    /** @brief
-     * Shared pointer to nodehandle.
-     */
-    boost::shared_ptr<ros::NodeHandle> nh_;
-
-    /** @brief
-     * Shared pointer to private nodehandle.
-     */
-    boost::shared_ptr<ros::NodeHandle> pnh_;
-
-    /** @brief
-     * WallTimer instance for warning about no connection.
-     */
-    ros::WallTimer timer_;
-
-    /** @brief
-     * A flag to check if any publisher is already subscribed
-     * or not.
-     */
-    bool 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 ~always_subscribe parameter.
-     */
-    bool always_subscribe_;
-
-    /** @brief
-     * Status of connection
-     */
-    ConnectionStatus connection_status_;
-
-    /** @brief
-     * true if `~verbose_connection` or `verbose_connection` parameter is true.
-     */
-    bool verbose_connection_;
-  private:
-    
-  };
-}
-
-#endif
diff --git a/opencv_apps/package.xml b/opencv_apps/package.xml
index c3ff225..5d48b1e 100644
--- a/opencv_apps/package.xml
+++ b/opencv_apps/package.xml
@@ -1,7 +1,7 @@
 <?xml version="1.0"?>
 <package>
   <name>opencv_apps</name>
-  <version>1.12.0</version>
+  <version>1.11.11</version>
   <description>The opencv_apps package, most of code is taken from https://github.com/Itseez/opencv/tree/master/samples/cpp</description>
 
   <maintainer email="kei.okada at gmail.com">Kei Okada</maintainer>
@@ -17,7 +17,6 @@
   <build_depend>message_generation</build_depend>
   <build_depend>nodelet</build_depend>
   <build_depend>roscpp</build_depend>
-  <build_depend>std_msgs</build_depend>
   <build_depend>std_srvs</build_depend>
 
   <run_depend>cv_bridge</run_depend>
@@ -26,7 +25,6 @@
   <run_depend>message_runtime</run_depend>
   <run_depend>nodelet</run_depend>
   <run_depend>roscpp</run_depend>
-  <run_depend>std_msgs</run_depend>
   <run_depend>std_srvs</run_depend>
 
   <test_depend>rostest</test_depend>
diff --git a/opencv_apps/src/nodelet/camshift_nodelet.cpp b/opencv_apps/src/nodelet/camshift_nodelet.cpp
index e487709..8c2f6e3 100644
--- a/opencv_apps/src/nodelet/camshift_nodelet.cpp
+++ b/opencv_apps/src/nodelet/camshift_nodelet.cpp
@@ -40,7 +40,7 @@
  */
 
 #include <ros/ros.h>
-#include "opencv_apps/nodelet.h"
+#include <nodelet/nodelet.h>
 #include <image_transport/image_transport.h>
 #include <sensor_msgs/image_encodings.h>
 #include <cv_bridge/cv_bridge.h>
@@ -56,7 +56,7 @@
 #include "opencv_apps/RotatedRectStamped.h"
 
 namespace camshift {
-class CamShiftNodelet : public opencv_apps::Nodelet
+class CamShiftNodelet : public nodelet::Nodelet
 {
   image_transport::Publisher img_pub_, bproj_pub_;
   image_transport::Subscriber img_sub_;
@@ -64,11 +64,13 @@ class CamShiftNodelet : public opencv_apps::Nodelet
   ros::Publisher msg_pub_;
 
   boost::shared_ptr<image_transport::ImageTransport> it_;
+  ros::NodeHandle nh_, local_nh_;
 
   camshift::CamShiftConfig config_;
   dynamic_reconfigure::Server<camshift::CamShiftConfig> srv;
 
   bool debug_view_;
+  int subscriber_count_;
   ros::Time prev_stamp_;
 
   std::string window_name_, histogram_name_;
@@ -108,6 +110,11 @@ class CamShiftNodelet : public opencv_apps::Nodelet
     vmin_ = config_.vmin;
     vmax_ = config_.vmax;
     smin_ = config_.smin;
+    if (subscriber_count_)
+    { // @todo Could do this without an interruption at some point.
+      unsubscribe();
+      subscribe();
+    }
   }
 
   const std::string &frameWithDefault(const std::string &frame, const std::string &image_frame)
@@ -220,7 +227,7 @@ class CamShiftNodelet : public opencv_apps::Nodelet
             std::vector<float> hist_value;
             hist_value.resize(hsize);
             for(int i = 0; i < hsize; i ++) { hist_value[i] = hist.at<float>(i);}
-            pnh_->setParam("histogram", hist_value);
+            local_nh_.setParam("histogram", hist_value);
 
             trackWindow = selection;
             trackObject = 1;
@@ -346,16 +353,45 @@ class CamShiftNodelet : public opencv_apps::Nodelet
     cam_sub_.shutdown();
   }
 
+  void img_connectCb(const image_transport::SingleSubscriberPublisher& ssp)
+  {
+    if (subscriber_count_++ == 0) {
+      subscribe();
+    }
+  }
+
+  void img_disconnectCb(const image_transport::SingleSubscriberPublisher&)
+  {
+    subscriber_count_--;
+    if (subscriber_count_ == 0) {
+      unsubscribe();
+    }
+  }
+
+  void msg_connectCb(const ros::SingleSubscriberPublisher& ssp)
+  {
+    if (subscriber_count_++ == 0) {
+      subscribe();
+    }
+  }
+
+  void msg_disconnectCb(const ros::SingleSubscriberPublisher&)
+  {
+    subscriber_count_--;
+    if (subscriber_count_ == 0) {
+      unsubscribe();
+    }
+  }
+
 public:
   virtual void onInit()
   {
-    Nodelet::onInit();
-    it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
+    nh_ = getNodeHandle();
+    it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(nh_));
+    local_nh_ = ros::NodeHandle("~");
 
-    pnh_->param("debug_view", debug_view_, false);
-    if (debug_view_) {
-      always_subscribe_ = true;
-    }
+    local_nh_.param("debug_view", debug_view_, false);
+    subscriber_count_ = 0;
     prev_stamp_ = ros::Time(0, 0);
 
     window_name_ = "CamShift Demo";
@@ -374,15 +410,22 @@ public:
     phranges = hranges;
     histimg = cv::Mat::zeros(200, 320, CV_8UC3);
 
+    image_transport::SubscriberStatusCallback img_connect_cb    = boost::bind(&CamShiftNodelet::img_connectCb, this, _1);
+    image_transport::SubscriberStatusCallback img_disconnect_cb = boost::bind(&CamShiftNodelet::img_disconnectCb, this, _1);
+    ros::SubscriberStatusCallback msg_connect_cb    = boost::bind(&CamShiftNodelet::msg_connectCb, this, _1);
+    ros::SubscriberStatusCallback msg_disconnect_cb = boost::bind(&CamShiftNodelet::msg_disconnectCb, this, _1);
+    img_pub_ = image_transport::ImageTransport(local_nh_).advertise("image", 1, img_connect_cb, img_disconnect_cb);
+    bproj_pub_ = image_transport::ImageTransport(local_nh_).advertise("back_project", 1, img_connect_cb, img_disconnect_cb);
+    msg_pub_ = local_nh_.advertise<opencv_apps::RotatedRectStamped>("track_box", 1, msg_connect_cb, msg_disconnect_cb);
+        
+    if( debug_view_ ) {
+      subscriber_count_++;
+    }
+
     dynamic_reconfigure::Server<camshift::CamShiftConfig>::CallbackType f =
       boost::bind(&CamShiftNodelet::reconfigureCallback, this, _1, _2);
     srv.setCallback(f);
 
-    
-    img_pub_ = advertiseImage(*pnh_, "image", 1);
-    bproj_pub_ = advertiseImage(*pnh_, "back_project", 1);
-    msg_pub_ = advertise<opencv_apps::RotatedRectStamped>(*pnh_, "track_box", 1);
-    
     NODELET_INFO("Hot keys: ");
     NODELET_INFO("\tESC - quit the program");
     NODELET_INFO("\tc - stop the tracking");
@@ -392,7 +435,7 @@ public:
     NODELET_INFO("To initialize tracking, select the object with mouse");
 
     std::vector<float> hist_value;
-    pnh_->getParam("histogram", hist_value);
+    local_nh_.getParam("histogram", hist_value);
     if ( hist_value.size() == hsize ) {
       hist.create(hsize, 1, CV_32F);
       for(int i = 0; i < hsize; i ++) { hist.at<float>(i) = hist_value[i];}
@@ -415,7 +458,7 @@ public:
                        cv::Scalar(buf.at<cv::Vec3b>(i)), -1, 8 );
       }
     }
-    onInitPostProcess();
+
   }
 };
 bool CamShiftNodelet::need_config_update_ = false;
diff --git a/opencv_apps/src/nodelet/contour_moments_nodelet.cpp b/opencv_apps/src/nodelet/contour_moments_nodelet.cpp
index 97653f3..3a981d8 100644
--- a/opencv_apps/src/nodelet/contour_moments_nodelet.cpp
+++ b/opencv_apps/src/nodelet/contour_moments_nodelet.cpp
@@ -40,7 +40,7 @@
  */
 
 #include <ros/ros.h>
-#include "opencv_apps/nodelet.h"
+#include <nodelet/nodelet.h>
 #include <image_transport/image_transport.h>
 #include <sensor_msgs/image_encodings.h>
 #include <cv_bridge/cv_bridge.h>
@@ -55,7 +55,7 @@
 #include "opencv_apps/MomentArrayStamped.h"
 
 namespace contour_moments {
-class ContourMomentsNodelet : public opencv_apps::Nodelet
+class ContourMomentsNodelet : public nodelet::Nodelet
 {
   image_transport::Publisher img_pub_;
   image_transport::Subscriber img_sub_;
@@ -63,11 +63,13 @@ class ContourMomentsNodelet : public opencv_apps::Nodelet
   ros::Publisher msg_pub_;
 
   boost::shared_ptr<image_transport::ImageTransport> it_;
+  ros::NodeHandle nh_, local_nh_;
 
   contour_moments::ContourMomentsConfig config_;
   dynamic_reconfigure::Server<contour_moments::ContourMomentsConfig> srv;
 
   bool debug_view_;
+  int subscriber_count_;
   ros::Time prev_stamp_;
 
   int low_threshold_;
@@ -79,6 +81,11 @@ class ContourMomentsNodelet : public opencv_apps::Nodelet
   {
     config_ = new_config;
     low_threshold_ = config_.canny_low_threshold;
+    if (subscriber_count_)
+    { // @todo Could do this without an interruption at some point.
+      unsubscribe();
+      subscribe();
+    }
   }
 
   const std::string &frameWithDefault(const std::string &frame, const std::string &image_frame)
@@ -236,28 +243,64 @@ class ContourMomentsNodelet : public opencv_apps::Nodelet
     cam_sub_.shutdown();
   }
 
+  void img_connectCb(const image_transport::SingleSubscriberPublisher& ssp)
+  {
+    if (subscriber_count_++ == 0) {
+      subscribe();
+    }
+  }
+
+  void img_disconnectCb(const image_transport::SingleSubscriberPublisher&)
+  {
+    subscriber_count_--;
+    if (subscriber_count_ == 0) {
+      unsubscribe();
+    }
+  }
+
+  void msg_connectCb(const ros::SingleSubscriberPublisher& ssp)
+  {
+    if (subscriber_count_++ == 0) {
+      subscribe();
+    }
+  }
+
+  void msg_disconnectCb(const ros::SingleSubscriberPublisher&)
+  {
+    subscriber_count_--;
+    if (subscriber_count_ == 0) {
+      unsubscribe();
+    }
+  }
+
 public:
   virtual void onInit()
   {
-    Nodelet::onInit();
-    it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
+    nh_ = getNodeHandle();
+    it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(nh_));
+    local_nh_ = ros::NodeHandle("~");
 
-    pnh_->param("debug_view", debug_view_, false);
-    if (debug_view_) {
-      always_subscribe_ = true;
-    }
+    local_nh_.param("debug_view", debug_view_, false);
+    subscriber_count_ = 0;
     prev_stamp_ = ros::Time(0, 0);
 
     window_name_ = "Contours";
     low_threshold_ = 100; // only for canny
-    
+
+    image_transport::SubscriberStatusCallback img_connect_cb    = boost::bind(&ContourMomentsNodelet::img_connectCb, this, _1);
+    image_transport::SubscriberStatusCallback img_disconnect_cb = boost::bind(&ContourMomentsNodelet::img_disconnectCb, this, _1);
+    ros::SubscriberStatusCallback msg_connect_cb    = boost::bind(&ContourMomentsNodelet::msg_connectCb, this, _1);
+    ros::SubscriberStatusCallback msg_disconnect_cb = boost::bind(&ContourMomentsNodelet::msg_disconnectCb, this, _1);
+    img_pub_ = image_transport::ImageTransport(local_nh_).advertise("image", 1, img_connect_cb, img_disconnect_cb);
+    msg_pub_ = local_nh_.advertise<opencv_apps::MomentArrayStamped>("moments", 1, msg_connect_cb, msg_disconnect_cb);
+
+    if( debug_view_ ) {
+      subscriber_count_++;
+    }
+
     dynamic_reconfigure::Server<contour_moments::ContourMomentsConfig>::CallbackType f =
       boost::bind(&ContourMomentsNodelet::reconfigureCallback, this, _1, _2);
     srv.setCallback(f);
-
-    img_pub_ = advertiseImage(*pnh_, "image", 1);
-    msg_pub_ = advertise<opencv_apps::MomentArrayStamped>(*pnh_, "moments", 1);
-    onInitPostProcess();
   }
 };
 bool ContourMomentsNodelet::need_config_update_ = false;
diff --git a/opencv_apps/src/nodelet/convex_hull_nodelet.cpp b/opencv_apps/src/nodelet/convex_hull_nodelet.cpp
index 9461430..9b5fc4e 100644
--- a/opencv_apps/src/nodelet/convex_hull_nodelet.cpp
+++ b/opencv_apps/src/nodelet/convex_hull_nodelet.cpp
@@ -40,7 +40,7 @@
  */
 
 #include <ros/ros.h>
-#include "opencv_apps/nodelet.h"
+#include <nodelet/nodelet.h>
 #include <image_transport/image_transport.h>
 #include <sensor_msgs/image_encodings.h>
 #include <cv_bridge/cv_bridge.h>
@@ -55,7 +55,7 @@
 #include "opencv_apps/ContourArrayStamped.h"
 
 namespace convex_hull {
-class ConvexHullNodelet : public opencv_apps::Nodelet
+class ConvexHullNodelet : public nodelet::Nodelet
 {
   image_transport::Publisher img_pub_;
   image_transport::Subscriber img_sub_;
@@ -63,11 +63,13 @@ class ConvexHullNodelet : public opencv_apps::Nodelet
   ros::Publisher msg_pub_;
 
   boost::shared_ptr<image_transport::ImageTransport> it_;
+  ros::NodeHandle nh_, local_nh_;
 
   convex_hull::ConvexHullConfig config_;
   dynamic_reconfigure::Server<convex_hull::ConvexHullConfig> srv;
 
   bool debug_view_;
+  int subscriber_count_;
   ros::Time prev_stamp_;
 
   int threshold_;
@@ -79,6 +81,11 @@ class ConvexHullNodelet : public opencv_apps::Nodelet
   {
     config_ = new_config;
     threshold_ = config_.threshold;
+    if (subscriber_count_)
+    { // @todo Could do this without an interruption at some point.
+      unsubscribe();
+      subscribe();
+    }
   }
 
   const std::string &frameWithDefault(const std::string &frame, const std::string &image_frame)
@@ -208,29 +215,64 @@ class ConvexHullNodelet : public opencv_apps::Nodelet
     cam_sub_.shutdown();
   }
 
+  void img_connectCb(const image_transport::SingleSubscriberPublisher& ssp)
+  {
+    if (subscriber_count_++ == 0) {
+      subscribe();
+    }
+  }
+
+  void img_disconnectCb(const image_transport::SingleSubscriberPublisher&)
+  {
+    subscriber_count_--;
+    if (subscriber_count_ == 0) {
+      unsubscribe();
+    }
+  }
+
+  void msg_connectCb(const ros::SingleSubscriberPublisher& ssp)
+  {
+    if (subscriber_count_++ == 0) {
+      subscribe();
+    }
+  }
+
+  void msg_disconnectCb(const ros::SingleSubscriberPublisher&)
+  {
+    subscriber_count_--;
+    if (subscriber_count_ == 0) {
+      unsubscribe();
+    }
+  }
 
 public:
   virtual void onInit()
   {
-    Nodelet::onInit();
-    it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
+    nh_ = getNodeHandle();
+    it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(nh_));
+    local_nh_ = ros::NodeHandle("~");
 
-    pnh_->param("debug_view", debug_view_, false);
-    if (debug_view_) {
-      always_subscribe_ = true;
-    }
+    local_nh_.param("debug_view", debug_view_, false);
+    subscriber_count_ = 0;
     prev_stamp_ = ros::Time(0, 0);
 
     window_name_ = "Hull Demo";
     threshold_ = 100;
-    
+
+    image_transport::SubscriberStatusCallback img_connect_cb    = boost::bind(&ConvexHullNodelet::img_connectCb, this, _1);
+    image_transport::SubscriberStatusCallback img_disconnect_cb = boost::bind(&ConvexHullNodelet::img_disconnectCb, this, _1);
+    ros::SubscriberStatusCallback msg_connect_cb    = boost::bind(&ConvexHullNodelet::msg_connectCb, this, _1);
+    ros::SubscriberStatusCallback msg_disconnect_cb = boost::bind(&ConvexHullNodelet::msg_disconnectCb, this, _1);
+    img_pub_ = image_transport::ImageTransport(local_nh_).advertise("image", 1, img_connect_cb, img_disconnect_cb);
+    msg_pub_ = local_nh_.advertise<opencv_apps::ContourArrayStamped>("hulls", 1, msg_connect_cb, msg_disconnect_cb);
+
+    if( debug_view_ ) {
+      subscriber_count_++;
+    }
+
     dynamic_reconfigure::Server<convex_hull::ConvexHullConfig>::CallbackType f =
       boost::bind(&ConvexHullNodelet::reconfigureCallback, this, _1, _2);
     srv.setCallback(f);
-
-    img_pub_ = advertiseImage(*pnh_, "image", 1);
-    msg_pub_ = advertise<opencv_apps::ContourArrayStamped>(*pnh_, "hulls", 1);
-    onInitPostProcess();
   }
 };
 bool ConvexHullNodelet::need_config_update_ = false;
diff --git a/opencv_apps/src/nodelet/edge_detection_nodelet.cpp b/opencv_apps/src/nodelet/edge_detection_nodelet.cpp
index 860415e..0179183 100644
--- a/opencv_apps/src/nodelet/edge_detection_nodelet.cpp
+++ b/opencv_apps/src/nodelet/edge_detection_nodelet.cpp
@@ -50,7 +50,7 @@
  */
 
 #include <ros/ros.h>
-#include "opencv_apps/nodelet.h"
+#include <nodelet/nodelet.h>
 #include <image_transport/image_transport.h>
 #include <sensor_msgs/image_encodings.h>
 #include <cv_bridge/cv_bridge.h>
@@ -62,7 +62,7 @@
 #include "opencv_apps/EdgeDetectionConfig.h"
 
 namespace edge_detection {
-class EdgeDetectionNodelet : public opencv_apps::Nodelet
+class EdgeDetectionNodelet : public nodelet::Nodelet
 {
   image_transport::Publisher img_pub_;
   image_transport::Subscriber img_sub_;
@@ -70,11 +70,13 @@ class EdgeDetectionNodelet : public opencv_apps::Nodelet
   ros::Publisher msg_pub_;
 
   boost::shared_ptr<image_transport::ImageTransport> it_;
+  ros::NodeHandle nh_, local_nh_;
 
   edge_detection::EdgeDetectionConfig config_;
   dynamic_reconfigure::Server<edge_detection::EdgeDetectionConfig> srv;
 
   bool debug_view_;
+  int subscriber_count_;
   ros::Time prev_stamp_;
 
   int low_threshold_;
@@ -86,6 +88,11 @@ class EdgeDetectionNodelet : public opencv_apps::Nodelet
   {
     config_ = new_config;
     low_threshold_ = config_.canny_low_threshold;
+    if (subscriber_count_)
+    { // @todo Could do this without an interruption at some point.
+      unsubscribe();
+      subscribe();
+    }
   }
 
   const std::string &frameWithDefault(const std::string &frame, const std::string &image_frame)
@@ -247,29 +254,64 @@ class EdgeDetectionNodelet : public opencv_apps::Nodelet
     cam_sub_.shutdown();
   }
 
+  void img_connectCb(const image_transport::SingleSubscriberPublisher& ssp)
+  {
+    if (subscriber_count_++ == 0) {
+      subscribe();
+    }
+  }
+
+  void img_disconnectCb(const image_transport::SingleSubscriberPublisher&)
+  {
+    subscriber_count_--;
+    if (subscriber_count_ == 0) {
+      unsubscribe();
+    }
+  }
+
+  void msg_connectCb(const ros::SingleSubscriberPublisher& ssp)
+  {
+    if (subscriber_count_++ == 0) {
+      subscribe();
+    }
+  }
+
+  void msg_disconnectCb(const ros::SingleSubscriberPublisher&)
+  {
+    subscriber_count_--;
+    if (subscriber_count_ == 0) {
+      unsubscribe();
+    }
+  }
+
 public:
   virtual void onInit()
   {
-    Nodelet::onInit();
-    it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
+    nh_ = getNodeHandle();
+    it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(nh_));
+    local_nh_ = ros::NodeHandle("~");
 
-    pnh_->param("debug_view", debug_view_, false);
-    if (debug_view_) {
-      always_subscribe_ = true;
-    }
+    local_nh_.param("debug_view", debug_view_, false);
+    subscriber_count_ = 0;
     prev_stamp_ = ros::Time(0, 0);
 
     window_name_ = "Edge Detection Demo";
     low_threshold_ = 10; // only for canny
 
+    image_transport::SubscriberStatusCallback img_connect_cb    = boost::bind(&EdgeDetectionNodelet::img_connectCb, this, _1);
+    image_transport::SubscriberStatusCallback img_disconnect_cb = boost::bind(&EdgeDetectionNodelet::img_disconnectCb, this, _1);
+    ros::SubscriberStatusCallback msg_connect_cb    = boost::bind(&EdgeDetectionNodelet::msg_connectCb, this, _1);
+    ros::SubscriberStatusCallback msg_disconnect_cb = boost::bind(&EdgeDetectionNodelet::msg_disconnectCb, this, _1);
+    img_pub_ = image_transport::ImageTransport(local_nh_).advertise("image", 1, img_connect_cb, img_disconnect_cb);
+    //msg_pub_ = local_nh_.advertise<opencv_apps::LineArrayStamped>("lines", 1, msg_connect_cb, msg_disconnect_cb);
+
+    if( debug_view_ ) {
+      subscriber_count_++;
+    }
+
     dynamic_reconfigure::Server<edge_detection::EdgeDetectionConfig>::CallbackType f =
       boost::bind(&EdgeDetectionNodelet::reconfigureCallback, this, _1, _2);
     srv.setCallback(f);
-    
-    img_pub_ = advertiseImage(*pnh_, "image", 1);
-    //msg_pub_ = local_nh_.advertise<opencv_apps::LineArrayStamped>("lines", 1, msg_connect_cb, msg_disconnect_cb);
-
-    onInitPostProcess();
   }
 };
 bool EdgeDetectionNodelet::need_config_update_ = false;
diff --git a/opencv_apps/src/nodelet/face_detection_nodelet.cpp b/opencv_apps/src/nodelet/face_detection_nodelet.cpp
index 1b86178..a81197c 100644
--- a/opencv_apps/src/nodelet/face_detection_nodelet.cpp
+++ b/opencv_apps/src/nodelet/face_detection_nodelet.cpp
@@ -40,7 +40,7 @@
  */
 
 #include <ros/ros.h>
-#include "opencv_apps/nodelet.h"
+#include <nodelet/nodelet.h>
 #include <image_transport/image_transport.h>
 #include <cv_bridge/cv_bridge.h>
 
@@ -55,7 +55,7 @@
 #include "opencv_apps/FaceArrayStamped.h"
 
 namespace face_detection {
-class FaceDetectionNodelet : public opencv_apps::Nodelet
+class FaceDetectionNodelet : public nodelet::Nodelet
 {
   image_transport::Publisher img_pub_;
   image_transport::Subscriber img_sub_;
@@ -63,11 +63,13 @@ class FaceDetectionNodelet : public opencv_apps::Nodelet
   ros::Publisher msg_pub_;
 
   boost::shared_ptr<image_transport::ImageTransport> it_;
+  ros::NodeHandle nh_, local_nh_;
 
   face_detection::FaceDetectionConfig config_;
   dynamic_reconfigure::Server<face_detection::FaceDetectionConfig> srv;
 
   bool debug_view_;
+  int subscriber_count_;
   ros::Time prev_stamp_;
 
   cv::CascadeClassifier face_cascade_;
@@ -76,6 +78,11 @@ class FaceDetectionNodelet : public opencv_apps::Nodelet
   void reconfigureCallback(face_detection::FaceDetectionConfig &new_config, uint32_t level)
   {
     config_ = new_config;
+    if (subscriber_count_)
+    { // @todo Could do this without an interruption at some point.
+      unsubscribe();
+      subscribe();
+    }
   }
 
   const std::string &frameWithDefault(const std::string &frame, const std::string &image_frame)
@@ -195,33 +202,67 @@ class FaceDetectionNodelet : public opencv_apps::Nodelet
     cam_sub_.shutdown();
   }
 
+  void img_connectCb(const image_transport::SingleSubscriberPublisher& ssp)
+  {
+    if (subscriber_count_++ == 0) {
+      subscribe();
+    }
+  }
+
+  void img_disconnectCb(const image_transport::SingleSubscriberPublisher&)
+  {
+    subscriber_count_--;
+    if (subscriber_count_ == 0) {
+      unsubscribe();
+    }
+  }
+
+  void msg_connectCb(const ros::SingleSubscriberPublisher& ssp)
+  {
+    if (subscriber_count_++ == 0) {
+      subscribe();
+    }
+  }
+
+  void msg_disconnectCb(const ros::SingleSubscriberPublisher&)
+  {
+    subscriber_count_--;
+    if (subscriber_count_ == 0) {
+      unsubscribe();
+    }
+  }
+
 public:
   virtual void onInit()
   {
-    Nodelet::onInit();
-    it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
+    nh_ = getNodeHandle();
+    it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(nh_));
+    local_nh_ = ros::NodeHandle("~");
 
-    pnh_->param("debug_view", debug_view_, false);
-    if (debug_view_ ) {
-      always_subscribe_ = true;
-    }
+    local_nh_.param("debug_view", debug_view_, false);
+    subscriber_count_ = 0;
     prev_stamp_ = ros::Time(0, 0);
 
-    dynamic_reconfigure::Server<face_detection::FaceDetectionConfig>::CallbackType f =
-      boost::bind(&FaceDetectionNodelet::reconfigureCallback, this, _1, _2);
-    srv.setCallback(f);
-    
-    img_pub_ = advertiseImage(*pnh_, "image", 1);
-    msg_pub_ = advertise<opencv_apps::FaceArrayStamped>(*pnh_, "faces", 1);
+    image_transport::SubscriberStatusCallback img_connect_cb    = boost::bind(&FaceDetectionNodelet::img_connectCb, this, _1);
+    image_transport::SubscriberStatusCallback img_disconnect_cb = boost::bind(&FaceDetectionNodelet::img_disconnectCb, this, _1);
+    ros::SubscriberStatusCallback msg_connect_cb    = boost::bind(&FaceDetectionNodelet::msg_connectCb, this, _1);
+    ros::SubscriberStatusCallback msg_disconnect_cb = boost::bind(&FaceDetectionNodelet::msg_disconnectCb, this, _1);
+    img_pub_ = image_transport::ImageTransport(local_nh_).advertise("image", 1, img_connect_cb, img_disconnect_cb);
+    msg_pub_ = local_nh_.advertise<opencv_apps::FaceArrayStamped>("faces", 1, msg_connect_cb, msg_disconnect_cb);
 
+    if( debug_view_ ) {
+      subscriber_count_++;
+    }
     std::string face_cascade_name, eyes_cascade_name;
-    pnh_->param("face_cascade_name", face_cascade_name, std::string("/usr/share/opencv/haarcascades/haarcascade_frontalface_alt.xml"));
-    pnh_->param("eyes_cascade_name", eyes_cascade_name, std::string("/usr/share/opencv/haarcascades/haarcascade_eye_tree_eyeglasses.xml"));
+    local_nh_.param("face_cascade_name", face_cascade_name, std::string("/usr/share/opencv/haarcascades/haarcascade_frontalface_alt.xml"));
+    local_nh_.param("eyes_cascade_name", eyes_cascade_name, std::string("/usr/share/opencv/haarcascades/haarcascade_eye_tree_eyeglasses.xml"));
 
     if( !face_cascade_.load( face_cascade_name ) ){ NODELET_ERROR("--Error loading %s", face_cascade_name.c_str()); };
     if( !eyes_cascade_.load( eyes_cascade_name ) ){ NODELET_ERROR("--Error loading %s", eyes_cascade_name.c_str()); };
 
-    onInitPostProcess();
+    dynamic_reconfigure::Server<face_detection::FaceDetectionConfig>::CallbackType f =
+      boost::bind(&FaceDetectionNodelet::reconfigureCallback, this, _1, _2);
+    srv.setCallback(f);
   }
 };
 }
diff --git a/opencv_apps/src/nodelet/fback_flow_nodelet.cpp b/opencv_apps/src/nodelet/fback_flow_nodelet.cpp
index c033fdc..24dbc6e 100644
--- a/opencv_apps/src/nodelet/fback_flow_nodelet.cpp
+++ b/opencv_apps/src/nodelet/fback_flow_nodelet.cpp
@@ -39,7 +39,7 @@
  */
 
 #include <ros/ros.h>
-#include "opencv_apps/nodelet.h"
+#include <nodelet/nodelet.h>
 #include <image_transport/image_transport.h>
 #include <cv_bridge/cv_bridge.h>
 
@@ -52,7 +52,7 @@
 #include "opencv_apps/FlowArrayStamped.h"
 
 namespace fback_flow {
-class FBackFlowNodelet : public opencv_apps::Nodelet
+class FBackFlowNodelet : public nodelet::Nodelet
 {
   image_transport::Publisher img_pub_;
   image_transport::Subscriber img_sub_;
@@ -60,11 +60,13 @@ class FBackFlowNodelet : public opencv_apps::Nodelet
   ros::Publisher msg_pub_;
 
   boost::shared_ptr<image_transport::ImageTransport> it_;
+  ros::NodeHandle nh_, local_nh_;
 
   fback_flow::FBackFlowConfig config_;
   dynamic_reconfigure::Server<fback_flow::FBackFlowConfig> srv;
 
   bool debug_view_;
+  int subscriber_count_;
   ros::Time prev_stamp_;
 
   std::string window_name_;
@@ -75,6 +77,11 @@ class FBackFlowNodelet : public opencv_apps::Nodelet
   void reconfigureCallback(fback_flow::FBackFlowConfig &new_config, uint32_t level)
   {
     config_ = new_config;
+    if (subscriber_count_)
+    { // @todo Could do this without an interruption at some point.
+      unsubscribe();
+      subscribe();
+    }
   }
 
   const std::string &frameWithDefault(const std::string &frame, const std::string &image_frame)
@@ -191,28 +198,63 @@ class FBackFlowNodelet : public opencv_apps::Nodelet
     cam_sub_.shutdown();
   }
 
+  void img_connectCb(const image_transport::SingleSubscriberPublisher& ssp)
+  {
+    if (subscriber_count_++ == 0) {
+      subscribe();
+    }
+  }
+
+  void img_disconnectCb(const image_transport::SingleSubscriberPublisher&)
+  {
+    subscriber_count_--;
+    if (subscriber_count_ == 0) {
+      unsubscribe();
+    }
+  }
+
+  void msg_connectCb(const ros::SingleSubscriberPublisher& ssp)
+  {
+    if (subscriber_count_++ == 0) {
+      subscribe();
+    }
+  }
+
+  void msg_disconnectCb(const ros::SingleSubscriberPublisher&)
+  {
+    subscriber_count_--;
+    if (subscriber_count_ == 0) {
+      unsubscribe();
+    }
+  }
+
 public:
   virtual void onInit()
   {
-    Nodelet::onInit();
-    it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
+    nh_ = getNodeHandle();
+    it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(nh_));
+    local_nh_ = ros::NodeHandle("~");
 
-    pnh_->param("debug_view", debug_view_, false);
-    if (debug_view_) {
-      always_subscribe_ = true;
-    }
+    local_nh_.param("debug_view", debug_view_, false);
+    subscriber_count_ = 0;
     prev_stamp_ = ros::Time(0, 0);
 
     window_name_ = "flow";
-    
+
+    image_transport::SubscriberStatusCallback img_connect_cb    = boost::bind(&FBackFlowNodelet::img_connectCb, this, _1);
+    image_transport::SubscriberStatusCallback img_disconnect_cb = boost::bind(&FBackFlowNodelet::img_disconnectCb, this, _1);
+    ros::SubscriberStatusCallback msg_connect_cb    = boost::bind(&FBackFlowNodelet::msg_connectCb, this, _1);
+    ros::SubscriberStatusCallback msg_disconnect_cb = boost::bind(&FBackFlowNodelet::msg_disconnectCb, this, _1);
+    img_pub_ = image_transport::ImageTransport(local_nh_).advertise("image", 1, img_connect_cb, img_disconnect_cb);
+    msg_pub_ = local_nh_.advertise<opencv_apps::FlowArrayStamped>("flows", 1, msg_connect_cb, msg_disconnect_cb);
+
+    if( debug_view_ ) {
+      subscriber_count_++;
+    }
+
     dynamic_reconfigure::Server<fback_flow::FBackFlowConfig>::CallbackType f =
       boost::bind(&FBackFlowNodelet::reconfigureCallback, this, _1, _2);
     srv.setCallback(f);
-
-    img_pub_ = advertiseImage(*pnh_, "image", 1);
-    msg_pub_ = advertise<opencv_apps::FlowArrayStamped>(*pnh_, "flows", 1);
-
-    onInitPostProcess();
   }
 };
 bool FBackFlowNodelet::need_config_update_ = false;
diff --git a/opencv_apps/src/nodelet/find_contours_nodelet.cpp b/opencv_apps/src/nodelet/find_contours_nodelet.cpp
index 085763c..dd1398a 100644
--- a/opencv_apps/src/nodelet/find_contours_nodelet.cpp
+++ b/opencv_apps/src/nodelet/find_contours_nodelet.cpp
@@ -40,7 +40,7 @@
  */
 
 #include <ros/ros.h>
-#include "opencv_apps/nodelet.h"
+#include <nodelet/nodelet.h>
 #include <image_transport/image_transport.h>
 #include <sensor_msgs/image_encodings.h>
 #include <cv_bridge/cv_bridge.h>
@@ -55,7 +55,7 @@
 #include "opencv_apps/ContourArrayStamped.h"
 
 namespace find_contours {
-class FindContoursNodelet : public opencv_apps::Nodelet
+class FindContoursNodelet : public nodelet::Nodelet
 {
   image_transport::Publisher img_pub_;
   image_transport::Subscriber img_sub_;
@@ -63,11 +63,13 @@ class FindContoursNodelet : public opencv_apps::Nodelet
   ros::Publisher msg_pub_;
 
   boost::shared_ptr<image_transport::ImageTransport> it_;
+  ros::NodeHandle nh_, local_nh_;
 
   find_contours::FindContoursConfig config_;
   dynamic_reconfigure::Server<find_contours::FindContoursConfig> srv;
 
   bool debug_view_;
+  int subscriber_count_;
   ros::Time prev_stamp_;
 
   int low_threshold_;
@@ -79,6 +81,11 @@ class FindContoursNodelet : public opencv_apps::Nodelet
   {
     config_ = new_config;
     low_threshold_ = config_.canny_low_threshold;
+    if (subscriber_count_)
+    { // @todo Could do this without an interruption at some point.
+      unsubscribe();
+      subscribe();
+    }
   }
 
   const std::string &frameWithDefault(const std::string &frame, const std::string &image_frame)
@@ -205,29 +212,64 @@ class FindContoursNodelet : public opencv_apps::Nodelet
     cam_sub_.shutdown();
   }
 
+  void img_connectCb(const image_transport::SingleSubscriberPublisher& ssp)
+  {
+    if (subscriber_count_++ == 0) {
+      subscribe();
+    }
+  }
+
+  void img_disconnectCb(const image_transport::SingleSubscriberPublisher&)
+  {
+    subscriber_count_--;
+    if (subscriber_count_ == 0) {
+      unsubscribe();
+    }
+  }
+
+  void msg_connectCb(const ros::SingleSubscriberPublisher& ssp)
+  {
+    if (subscriber_count_++ == 0) {
+      subscribe();
+    }
+  }
+
+  void msg_disconnectCb(const ros::SingleSubscriberPublisher&)
+  {
+    subscriber_count_--;
+    if (subscriber_count_ == 0) {
+      unsubscribe();
+    }
+  }
+
 public:
   virtual void onInit()
   {
-    Nodelet::onInit();
-    it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
+    nh_ = getNodeHandle();
+    it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(nh_));
+    local_nh_ = ros::NodeHandle("~");
 
-    pnh_->param("debug_view", debug_view_, false);
-    if (debug_view_) {
-      always_subscribe_ = true;
-    }
+    local_nh_.param("debug_view", debug_view_, false);
+    subscriber_count_ = 0;
     prev_stamp_ = ros::Time(0, 0);
 
     window_name_ = "Demo code to find contours in an image";
     low_threshold_ = 100; // only for canny
-    
+
+    image_transport::SubscriberStatusCallback img_connect_cb    = boost::bind(&FindContoursNodelet::img_connectCb, this, _1);
+    image_transport::SubscriberStatusCallback img_disconnect_cb = boost::bind(&FindContoursNodelet::img_disconnectCb, this, _1);
+    ros::SubscriberStatusCallback msg_connect_cb    = boost::bind(&FindContoursNodelet::msg_connectCb, this, _1);
+    ros::SubscriberStatusCallback msg_disconnect_cb = boost::bind(&FindContoursNodelet::msg_disconnectCb, this, _1);
+    img_pub_ = image_transport::ImageTransport(local_nh_).advertise("image", 1, img_connect_cb, img_disconnect_cb);
+    msg_pub_ = local_nh_.advertise<opencv_apps::ContourArrayStamped>("contours", 1, msg_connect_cb, msg_disconnect_cb);
+        
+    if( debug_view_ ) {
+      subscriber_count_++;
+    }
+
     dynamic_reconfigure::Server<find_contours::FindContoursConfig>::CallbackType f =
       boost::bind(&FindContoursNodelet::reconfigureCallback, this, _1, _2);
     srv.setCallback(f);
-
-    img_pub_ = advertiseImage(*pnh_, "image", 1);
-    msg_pub_ = advertise<opencv_apps::ContourArrayStamped>(*pnh_, "contours", 1);
-
-    onInitPostProcess();
   }
 };
 bool FindContoursNodelet::need_config_update_ = false;
diff --git a/opencv_apps/src/nodelet/general_contours_nodelet.cpp b/opencv_apps/src/nodelet/general_contours_nodelet.cpp
index 7b4a946..46e8a86 100644
--- a/opencv_apps/src/nodelet/general_contours_nodelet.cpp
+++ b/opencv_apps/src/nodelet/general_contours_nodelet.cpp
@@ -40,7 +40,7 @@
  */
 
 #include <ros/ros.h>
-#include "opencv_apps/nodelet.h"
+#include <nodelet/nodelet.h>
 #include <image_transport/image_transport.h>
 #include <sensor_msgs/image_encodings.h>
 #include <cv_bridge/cv_bridge.h>
@@ -55,7 +55,7 @@
 #include "opencv_apps/RotatedRectArrayStamped.h"
 
 namespace general_contours {
-class GeneralContoursNodelet : public opencv_apps::Nodelet
+class GeneralContoursNodelet : public nodelet::Nodelet
 {
   image_transport::Publisher img_pub_;
   image_transport::Subscriber img_sub_;
@@ -63,11 +63,13 @@ class GeneralContoursNodelet : public opencv_apps::Nodelet
   ros::Publisher rects_pub_, ellipses_pub_;
 
   boost::shared_ptr<image_transport::ImageTransport> it_;
+  ros::NodeHandle nh_, local_nh_;
 
   general_contours::GeneralContoursConfig config_;
   dynamic_reconfigure::Server<general_contours::GeneralContoursConfig> srv;
 
   bool debug_view_;
+  int subscriber_count_;
   ros::Time prev_stamp_;
 
   int threshold_;
@@ -79,6 +81,11 @@ class GeneralContoursNodelet : public opencv_apps::Nodelet
   {
     config_ = new_config;
     threshold_ = config_.threshold;
+    if (subscriber_count_)
+    { // @todo Could do this without an interruption at some point.
+      unsubscribe();
+      subscribe();
+    }
   }
 
   const std::string &frameWithDefault(const std::string &frame, const std::string &image_frame)
@@ -236,30 +243,65 @@ class GeneralContoursNodelet : public opencv_apps::Nodelet
     cam_sub_.shutdown();
   }
 
+  void img_connectCb(const image_transport::SingleSubscriberPublisher& ssp)
+  {
+    if (subscriber_count_++ == 0) {
+      subscribe();
+    }
+  }
+
+  void img_disconnectCb(const image_transport::SingleSubscriberPublisher&)
+  {
+    subscriber_count_--;
+    if (subscriber_count_ == 0) {
+      unsubscribe();
+    }
+  }
+
+  void msg_connectCb(const ros::SingleSubscriberPublisher& ssp)
+  {
+    if (subscriber_count_++ == 0) {
+      subscribe();
+    }
+  }
+
+  void msg_disconnectCb(const ros::SingleSubscriberPublisher&)
+  {
+    subscriber_count_--;
+    if (subscriber_count_ == 0) {
+      unsubscribe();
+    }
+  }
+
 public:
   virtual void onInit()
   {
-    Nodelet::onInit();
-    it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
+    nh_ = getNodeHandle();
+    it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(nh_));
+    local_nh_ = ros::NodeHandle("~");
 
-    pnh_->param("debug_view", debug_view_, false);
-    if (debug_view_) {
-      always_subscribe_ = true;
-    }
+    local_nh_.param("debug_view", debug_view_, false);
+    subscriber_count_ = 0;
     prev_stamp_ = ros::Time(0, 0);
 
     window_name_ = "Contours";
     threshold_ = 100;
 
+    image_transport::SubscriberStatusCallback img_connect_cb    = boost::bind(&GeneralContoursNodelet::img_connectCb, this, _1);
+    image_transport::SubscriberStatusCallback img_disconnect_cb = boost::bind(&GeneralContoursNodelet::img_disconnectCb, this, _1);
+    ros::SubscriberStatusCallback msg_connect_cb    = boost::bind(&GeneralContoursNodelet::msg_connectCb, this, _1);
+    ros::SubscriberStatusCallback msg_disconnect_cb = boost::bind(&GeneralContoursNodelet::msg_disconnectCb, this, _1);
+    img_pub_ = image_transport::ImageTransport(local_nh_).advertise("image", 1, img_connect_cb, img_disconnect_cb);
+    rects_pub_ = local_nh_.advertise<opencv_apps::RotatedRectArrayStamped>("rectangles", 1, msg_connect_cb, msg_disconnect_cb);
+    ellipses_pub_ = local_nh_.advertise<opencv_apps::RotatedRectArrayStamped>("ellipses", 1, msg_connect_cb, msg_disconnect_cb);
+
+    if( debug_view_ ) {
+      subscriber_count_++;
+    }
+
     dynamic_reconfigure::Server<general_contours::GeneralContoursConfig>::CallbackType f =
       boost::bind(&GeneralContoursNodelet::reconfigureCallback, this, _1, _2);
     srv.setCallback(f);
-    
-    img_pub_ = advertiseImage(*pnh_, "image", 1);
-    rects_pub_ = advertise<opencv_apps::RotatedRectArrayStamped>(*pnh_, "rectangles", 1);
-    ellipses_pub_ = advertise<opencv_apps::RotatedRectArrayStamped>(*pnh_, "ellipses", 1);
-
-    onInitPostProcess();
   }
 };
 bool GeneralContoursNodelet::need_config_update_ = false;
diff --git a/opencv_apps/src/nodelet/goodfeature_track_nodelet.cpp b/opencv_apps/src/nodelet/goodfeature_track_nodelet.cpp
index 7377551..e37704a 100644
--- a/opencv_apps/src/nodelet/goodfeature_track_nodelet.cpp
+++ b/opencv_apps/src/nodelet/goodfeature_track_nodelet.cpp
@@ -40,7 +40,7 @@
  */
 
 #include <ros/ros.h>
-#include "opencv_apps/nodelet.h"
+#include <nodelet/nodelet.h>
 #include <image_transport/image_transport.h>
 #include <cv_bridge/cv_bridge.h>
 
@@ -53,7 +53,7 @@
 #include "opencv_apps/Point2DArrayStamped.h"
 
 namespace goodfeature_track {
-class GoodfeatureTrackNodelet : public opencv_apps::Nodelet
+class GoodfeatureTrackNodelet : public nodelet::Nodelet
 {
   image_transport::Publisher img_pub_;
   image_transport::Subscriber img_sub_;
@@ -61,11 +61,13 @@ class GoodfeatureTrackNodelet : public opencv_apps::Nodelet
   ros::Publisher msg_pub_;
 
   boost::shared_ptr<image_transport::ImageTransport> it_;
+  ros::NodeHandle nh_, local_nh_;
 
   goodfeature_track::GoodfeatureTrackConfig config_;
   dynamic_reconfigure::Server<goodfeature_track::GoodfeatureTrackConfig> srv;
 
   bool debug_view_;
+  int subscriber_count_;
   ros::Time prev_stamp_;
 
   std::string window_name_;
@@ -77,6 +79,11 @@ class GoodfeatureTrackNodelet : public opencv_apps::Nodelet
   {
     config_ = new_config;
     max_corners_ = config_.max_corners;
+    if (subscriber_count_)
+    { // @todo Could do this without an interruption at some point.
+      unsubscribe();
+      subscribe();
+    }
   }
 
   const std::string &frameWithDefault(const std::string &frame, const std::string &image_frame)
@@ -208,29 +215,64 @@ class GoodfeatureTrackNodelet : public opencv_apps::Nodelet
     cam_sub_.shutdown();
   }
 
+  void img_connectCb(const image_transport::SingleSubscriberPublisher& ssp)
+  {
+    if (subscriber_count_++ == 0) {
+      subscribe();
+    }
+  }
+
+  void img_disconnectCb(const image_transport::SingleSubscriberPublisher&)
+  {
+    subscriber_count_--;
+    if (subscriber_count_ == 0) {
+      unsubscribe();
+    }
+  }
+
+  void msg_connectCb(const ros::SingleSubscriberPublisher& ssp)
+  {
+    if (subscriber_count_++ == 0) {
+      subscribe();
+    }
+  }
+
+  void msg_disconnectCb(const ros::SingleSubscriberPublisher&)
+  {
+    subscriber_count_--;
+    if (subscriber_count_ == 0) {
+      unsubscribe();
+    }
+  }
+
 public:
   virtual void onInit()
   {
-    Nodelet::onInit();
-    it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
+    nh_ = getNodeHandle();
+    it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(nh_));
+    local_nh_ = ros::NodeHandle("~");
 
-    pnh_->param("debug_view", debug_view_, false);
-    if (debug_view_) {
-      always_subscribe_ = true;
-    }
+    local_nh_.param("debug_view", debug_view_, false);
+    subscriber_count_ = 0;
     prev_stamp_ = ros::Time(0, 0);
 
     window_name_ = "Image";
     max_corners_ = 23;
 
+    image_transport::SubscriberStatusCallback img_connect_cb    = boost::bind(&GoodfeatureTrackNodelet::img_connectCb, this, _1);
+    image_transport::SubscriberStatusCallback img_disconnect_cb = boost::bind(&GoodfeatureTrackNodelet::img_disconnectCb, this, _1);
+    ros::SubscriberStatusCallback msg_connect_cb    = boost::bind(&GoodfeatureTrackNodelet::msg_connectCb, this, _1);
+    ros::SubscriberStatusCallback msg_disconnect_cb = boost::bind(&GoodfeatureTrackNodelet::msg_disconnectCb, this, _1);
+    img_pub_ = image_transport::ImageTransport(local_nh_).advertise("image", 1, img_connect_cb, img_disconnect_cb);
+    msg_pub_ = local_nh_.advertise<opencv_apps::Point2DArrayStamped>("corners", 1, msg_connect_cb, msg_disconnect_cb);
+
+    if( debug_view_ ) {
+      subscriber_count_++;
+    }
+
     dynamic_reconfigure::Server<goodfeature_track::GoodfeatureTrackConfig>::CallbackType f =
       boost::bind(&GoodfeatureTrackNodelet::reconfigureCallback, this, _1, _2);
     srv.setCallback(f);
-    
-    img_pub_ = advertiseImage(*pnh_, "image", 1);
-    msg_pub_ = advertise<opencv_apps::Point2DArrayStamped>(*pnh_, "corners", 1);
-
-    onInitPostProcess();
   }
 };
 bool GoodfeatureTrackNodelet::need_config_update_ = false;
diff --git a/opencv_apps/src/nodelet/hough_circles_nodelet.cpp b/opencv_apps/src/nodelet/hough_circles_nodelet.cpp
index b5b94ea..99becfa 100644
--- a/opencv_apps/src/nodelet/hough_circles_nodelet.cpp
+++ b/opencv_apps/src/nodelet/hough_circles_nodelet.cpp
@@ -40,7 +40,7 @@
  */
 
 #include <ros/ros.h>
-#include "opencv_apps/nodelet.h"
+#include <nodelet/nodelet.h>
 #include <image_transport/image_transport.h>
 #include <cv_bridge/cv_bridge.h>
 
@@ -54,7 +54,7 @@
 #include "opencv_apps/CircleArrayStamped.h"
 
 namespace hough_circles {
-class HoughCirclesNodelet : public opencv_apps::Nodelet
+class HoughCirclesNodelet : public nodelet::Nodelet
 {
   image_transport::Publisher img_pub_;
   image_transport::Subscriber img_sub_;
@@ -62,11 +62,13 @@ class HoughCirclesNodelet : public opencv_apps::Nodelet
   ros::Publisher msg_pub_;
 
   boost::shared_ptr<image_transport::ImageTransport> it_;
+  ros::NodeHandle nh_, local_nh_;
 
   hough_circles::HoughCirclesConfig config_;
   dynamic_reconfigure::Server<hough_circles::HoughCirclesConfig> srv;
 
   bool debug_view_;
+  int subscriber_count_;
   ros::Time prev_stamp_;
 
   std::string window_name_;
@@ -86,6 +88,11 @@ class HoughCirclesNodelet : public opencv_apps::Nodelet
     config_ = new_config;
     canny_threshold_ = config_.canny_threshold;
     accumulator_threshold_ = config_.accumulator_threshold;
+    if (subscriber_count_)
+    { // @todo Could do this without an interruption at some point.
+      unsubscribe();
+      subscribe();
+    }
   }
 
   const std::string &frameWithDefault(const std::string &frame, const std::string &image_frame)
@@ -214,16 +221,45 @@ class HoughCirclesNodelet : public opencv_apps::Nodelet
     cam_sub_.shutdown();
   }
 
+  void img_connectCb(const image_transport::SingleSubscriberPublisher& ssp)
+  {
+    if (subscriber_count_++ == 0) {
+      subscribe();
+    }
+  }
+
+  void img_disconnectCb(const image_transport::SingleSubscriberPublisher&)
+  {
+    subscriber_count_--;
+    if (subscriber_count_ == 0) {
+      unsubscribe();
+    }
+  }
+
+  void msg_connectCb(const ros::SingleSubscriberPublisher& ssp)
+  {
+    if (subscriber_count_++ == 0) {
+      subscribe();
+    }
+  }
+
+  void msg_disconnectCb(const ros::SingleSubscriberPublisher&)
+  {
+    subscriber_count_--;
+    if (subscriber_count_ == 0) {
+      unsubscribe();
+    }
+  }
+
 public:
   virtual void onInit()
   {
-    Nodelet::onInit();
-    it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
+    nh_ = getNodeHandle();
+    it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(nh_));
+    local_nh_ = ros::NodeHandle("~");
 
-    pnh_->param("debug_view", debug_view_, false);
-    if (debug_view_) {
-      always_subscribe_ = debug_view_;
-    }
+    local_nh_.param("debug_view", debug_view_, false);
+    subscriber_count_ = 0;
     prev_stamp_ = ros::Time(0, 0);
 
     window_name_ = "Hough Circle Detection Demo";
@@ -235,15 +271,21 @@ public:
     //declare and initialize both parameters that are subjects to change
     canny_threshold_ = canny_threshold_initial_value_;
     accumulator_threshold_ = accumulator_threshold_initial_value_;
-    
+
+    image_transport::SubscriberStatusCallback img_connect_cb    = boost::bind(&HoughCirclesNodelet::img_connectCb, this, _1);
+    image_transport::SubscriberStatusCallback img_disconnect_cb = boost::bind(&HoughCirclesNodelet::img_disconnectCb, this, _1);
+    ros::SubscriberStatusCallback msg_connect_cb    = boost::bind(&HoughCirclesNodelet::msg_connectCb, this, _1);
+    ros::SubscriberStatusCallback msg_disconnect_cb = boost::bind(&HoughCirclesNodelet::msg_disconnectCb, this, _1);
+    img_pub_ = image_transport::ImageTransport(local_nh_).advertise("image", 1, img_connect_cb, img_disconnect_cb);
+    msg_pub_ = local_nh_.advertise<opencv_apps::CircleArrayStamped>("circles", 1, msg_connect_cb, msg_disconnect_cb);
+
+    if( debug_view_ ) {
+      subscriber_count_++;
+    }
+
     dynamic_reconfigure::Server<hough_circles::HoughCirclesConfig>::CallbackType f =
       boost::bind(&HoughCirclesNodelet::reconfigureCallback, this, _1, _2);
     srv.setCallback(f);
-
-    img_pub_ = advertiseImage(*pnh_, "image", 1);
-    msg_pub_ = advertise<opencv_apps::CircleArrayStamped>(*pnh_, "circles", 1);
-
-    onInitPostProcess();
   }
 };
 bool HoughCirclesNodelet::need_config_update_ = false;
diff --git a/opencv_apps/src/nodelet/hough_lines_nodelet.cpp b/opencv_apps/src/nodelet/hough_lines_nodelet.cpp
index b0e47a5..d12694f 100644
--- a/opencv_apps/src/nodelet/hough_lines_nodelet.cpp
+++ b/opencv_apps/src/nodelet/hough_lines_nodelet.cpp
@@ -40,7 +40,7 @@
  */
 
 #include <ros/ros.h>
-#include "opencv_apps/nodelet.h"
+#include <nodelet/nodelet.h>
 #include <image_transport/image_transport.h>
 #include <cv_bridge/cv_bridge.h>
 
@@ -54,7 +54,7 @@
 #include "opencv_apps/LineArrayStamped.h"
 
 namespace hough_lines {
-class HoughLinesNodelet : public opencv_apps::Nodelet
+class HoughLinesNodelet : public nodelet::Nodelet
 {
   image_transport::Publisher img_pub_;
   image_transport::Subscriber img_sub_;
@@ -62,11 +62,13 @@ class HoughLinesNodelet : public opencv_apps::Nodelet
   ros::Publisher msg_pub_;
 
   boost::shared_ptr<image_transport::ImageTransport> it_;
+  ros::NodeHandle nh_, local_nh_;
 
   hough_lines::HoughLinesConfig config_;
   dynamic_reconfigure::Server<hough_lines::HoughLinesConfig> srv;
 
   bool debug_view_;
+  int subscriber_count_;
   ros::Time prev_stamp_;
 
   std::string window_name_;
@@ -80,6 +82,11 @@ class HoughLinesNodelet : public opencv_apps::Nodelet
   {
     config_ = new_config;
     threshold_ = config_.threshold;
+    if (subscriber_count_)
+    { // @todo Could do this without an interruption at some point.
+      unsubscribe();
+      subscribe();
+    }
   }
 
   const std::string &frameWithDefault(const std::string &frame, const std::string &image_frame)
@@ -242,16 +249,45 @@ class HoughLinesNodelet : public opencv_apps::Nodelet
     cam_sub_.shutdown();
   }
 
+  void img_connectCb(const image_transport::SingleSubscriberPublisher& ssp)
+  {
+    if (subscriber_count_++ == 0) {
+      subscribe();
+    }
+  }
+
+  void img_disconnectCb(const image_transport::SingleSubscriberPublisher&)
+  {
+    subscriber_count_--;
+    if (subscriber_count_ == 0) {
+      unsubscribe();
+    }
+  }
+
+  void msg_connectCb(const ros::SingleSubscriberPublisher& ssp)
+  {
+    if (subscriber_count_++ == 0) {
+      subscribe();
+    }
+  }
+
+  void msg_disconnectCb(const ros::SingleSubscriberPublisher&)
+  {
+    subscriber_count_--;
+    if (subscriber_count_ == 0) {
+      unsubscribe();
+    }
+  }
+
 public:
   virtual void onInit()
   {
-    Nodelet::onInit();
-    it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
+    nh_ = getNodeHandle();
+    it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(nh_));
+    local_nh_ = ros::NodeHandle("~");
 
-    pnh_->param("debug_view", debug_view_, false);
-    if (debug_view_) {
-      always_subscribe_ = true;
-    }
+    local_nh_.param("debug_view", debug_view_, false);
+    subscriber_count_ = 0;
     prev_stamp_ = ros::Time(0, 0);
 
     window_name_ = "Hough Lines Demo";
@@ -259,14 +295,20 @@ public:
     max_threshold_ = 150;
     threshold_ = max_threshold_;
 
+    image_transport::SubscriberStatusCallback img_connect_cb    = boost::bind(&HoughLinesNodelet::img_connectCb, this, _1);
+    image_transport::SubscriberStatusCallback img_disconnect_cb = boost::bind(&HoughLinesNodelet::img_disconnectCb, this, _1);
+    ros::SubscriberStatusCallback msg_connect_cb    = boost::bind(&HoughLinesNodelet::msg_connectCb, this, _1);
+    ros::SubscriberStatusCallback msg_disconnect_cb = boost::bind(&HoughLinesNodelet::msg_disconnectCb, this, _1);
+    img_pub_ = image_transport::ImageTransport(local_nh_).advertise("image", 1, img_connect_cb, img_disconnect_cb);
+    msg_pub_ = local_nh_.advertise<opencv_apps::LineArrayStamped>("lines", 1, msg_connect_cb, msg_disconnect_cb);
+
+    if( debug_view_ ) {
+      subscriber_count_++;
+    }
+
     dynamic_reconfigure::Server<hough_lines::HoughLinesConfig>::CallbackType f =
       boost::bind(&HoughLinesNodelet::reconfigureCallback, this, _1, _2);
     srv.setCallback(f);
-    
-    img_pub_ = advertiseImage(*pnh_, "image", 1);
-    msg_pub_ = advertise<opencv_apps::LineArrayStamped>(*pnh_, "lines", 1);
-
-    onInitPostProcess();
   }
 };
 bool HoughLinesNodelet::need_config_update_ = false;
diff --git a/opencv_apps/src/nodelet/lk_flow_nodelet.cpp b/opencv_apps/src/nodelet/lk_flow_nodelet.cpp
index 400a425..c0ae5ed 100644
--- a/opencv_apps/src/nodelet/lk_flow_nodelet.cpp
+++ b/opencv_apps/src/nodelet/lk_flow_nodelet.cpp
@@ -38,7 +38,7 @@
  */
 
 #include <ros/ros.h>
-#include "opencv_apps/nodelet.h"
+#include <nodelet/nodelet.h>
 #include <image_transport/image_transport.h>
 #include <cv_bridge/cv_bridge.h>
 
@@ -52,7 +52,7 @@
 #include "opencv_apps/FlowArrayStamped.h"
 
 namespace lk_flow {
-class LKFlowNodelet : public opencv_apps::Nodelet
+class LKFlowNodelet : public nodelet::Nodelet
 {
   image_transport::Publisher img_pub_;
   image_transport::Subscriber img_sub_;
@@ -63,11 +63,13 @@ class LKFlowNodelet : public opencv_apps::Nodelet
   ros::ServiceServer toggle_night_mode_service_;
 
   boost::shared_ptr<image_transport::ImageTransport> it_;
+  ros::NodeHandle nh_, local_nh_;
 
   lk_flow::LKFlowConfig config_;
   dynamic_reconfigure::Server<lk_flow::LKFlowConfig> srv;
 
   bool debug_view_;
+  int subscriber_count_;
   ros::Time prev_stamp_;
 
   std::string window_name_;
@@ -84,6 +86,11 @@ class LKFlowNodelet : public opencv_apps::Nodelet
   void reconfigureCallback(lk_flow::LKFlowConfig &new_config, uint32_t level)
   {
     config_ = new_config;
+    if (subscriber_count_)
+    { // @todo Could do this without an interruption at some point.
+      unsubscribe();
+      subscribe();
+    }
   }
 
   const std::string &frameWithDefault(const std::string &frame, const std::string &image_frame)
@@ -283,16 +290,45 @@ class LKFlowNodelet : public opencv_apps::Nodelet
     cam_sub_.shutdown();
   }
 
+  void img_connectCb(const image_transport::SingleSubscriberPublisher& ssp)
+  {
+    if (subscriber_count_++ == 0) {
+      subscribe();
+    }
+  }
+
+  void img_disconnectCb(const image_transport::SingleSubscriberPublisher&)
+  {
+    subscriber_count_--;
+    if (subscriber_count_ == 0) {
+      unsubscribe();
+    }
+  }
+
+  void msg_connectCb(const ros::SingleSubscriberPublisher& ssp)
+  {
+    if (subscriber_count_++ == 0) {
+      subscribe();
+    }
+  }
+
+  void msg_disconnectCb(const ros::SingleSubscriberPublisher&)
+  {
+    subscriber_count_--;
+    if (subscriber_count_ == 0) {
+      unsubscribe();
+    }
+  }
+
 public:
   virtual void onInit()
   {
-    Nodelet::onInit();
-    it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
+    nh_ = getNodeHandle();
+    it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(nh_));
+    local_nh_ = ros::NodeHandle("~");
 
-    pnh_->param("debug_view", debug_view_, false);
-    if (debug_view_) {
-      always_subscribe_ = true;
-    }
+    local_nh_.param("debug_view", debug_view_, false);
+    subscriber_count_ = 0;
     prev_stamp_ = ros::Time(0, 0);
 
     window_name_ = "LK Demo";
@@ -301,16 +337,23 @@ public:
     nightMode = false;
     addRemovePt = false;
 
+    image_transport::SubscriberStatusCallback img_connect_cb    = boost::bind(&LKFlowNodelet::img_connectCb, this, _1);
+    image_transport::SubscriberStatusCallback img_disconnect_cb = boost::bind(&LKFlowNodelet::img_disconnectCb, this, _1);
+    ros::SubscriberStatusCallback msg_connect_cb    = boost::bind(&LKFlowNodelet::msg_connectCb, this, _1);
+    ros::SubscriberStatusCallback msg_disconnect_cb = boost::bind(&LKFlowNodelet::msg_disconnectCb, this, _1);
+    img_pub_ = image_transport::ImageTransport(local_nh_).advertise("image", 1, img_connect_cb, img_disconnect_cb);
+    msg_pub_ = local_nh_.advertise<opencv_apps::FlowArrayStamped>("flows", 1, msg_connect_cb, msg_disconnect_cb);
+    initialize_points_service_ = local_nh_.advertiseService("initialize_points", &LKFlowNodelet::initialize_points_cb, this);
+    delete_points_service_ = local_nh_.advertiseService("delete_points", &LKFlowNodelet::delete_points_cb, this);
+    toggle_night_mode_service_ = local_nh_.advertiseService("toggle_night_mode", &LKFlowNodelet::toggle_night_mode_cb, this);
+
+    if( debug_view_ ) {
+      subscriber_count_++;
+    }
+
     dynamic_reconfigure::Server<lk_flow::LKFlowConfig>::CallbackType f =
       boost::bind(&LKFlowNodelet::reconfigureCallback, this, _1, _2);
     srv.setCallback(f);
-    
-    img_pub_ = advertiseImage(*pnh_, "image", 1);
-    msg_pub_ = advertise<opencv_apps::FlowArrayStamped>(*pnh_, "flows", 1);
-    initialize_points_service_ = pnh_->advertiseService("initialize_points", &LKFlowNodelet::initialize_points_cb, this);
-    delete_points_service_ = pnh_->advertiseService("delete_points", &LKFlowNodelet::delete_points_cb, this);
-    toggle_night_mode_service_ = pnh_->advertiseService("toggle_night_mode", &LKFlowNodelet::toggle_night_mode_cb, this);
-
 
     NODELET_INFO("Hot keys: ");
     NODELET_INFO("\tESC - quit the program");
@@ -318,8 +361,6 @@ public:
     NODELET_INFO("\tc - delete all the points");
     NODELET_INFO("\tn - switch the \"night\" mode on/off");
     //NODELET_INFO("To add/remove a feature point click it");
-
-    onInitPostProcess();
   }
 };
 bool LKFlowNodelet::need_config_update_ = false;
diff --git a/opencv_apps/src/nodelet/nodelet.cpp b/opencv_apps/src/nodelet/nodelet.cpp
deleted file mode 100644
index 5b8bdd5..0000000
--- a/opencv_apps/src/nodelet/nodelet.cpp
+++ /dev/null
@@ -1,184 +0,0 @@
-// -*- mode: c++ -*-
-/*********************************************************************
- * Software License Agreement (BSD License)
- *
- *  Copyright (c) 2016, Ryohei Ueda.
- *  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.
- *********************************************************************/
-
-#include "opencv_apps/nodelet.h"
-
-namespace opencv_apps
-{
-  void Nodelet::onInit()
-  {
-    connection_status_ = NOT_SUBSCRIBED;
-    nh_.reset (new ros::NodeHandle (getMTNodeHandle ()));
-    pnh_.reset (new ros::NodeHandle (getMTPrivateNodeHandle ()));
-    pnh_->param("always_subscribe", always_subscribe_, false);
-    pnh_->param("verbose_connection", verbose_connection_, false);
-    if (!verbose_connection_) {
-      nh_->param("verbose_connection", verbose_connection_, false);
-    }
-    // timer to warn when no connection in a few seconds
-    ever_subscribed_ = false;
-    timer_ = nh_->createWallTimer(
-      ros::WallDuration(5),
-      &Nodelet::warnNeverSubscribedCallback,
-      this,
-      /*oneshot=*/true);
-  }
-
-  void Nodelet::onInitPostProcess()
-  {
-    if (always_subscribe_) {
-      subscribe();
-    }
-  }
-
-  void Nodelet::warnNeverSubscribedCallback(const ros::WallTimerEvent& event)
-  {
-    if (!ever_subscribed_) {
-      NODELET_WARN("'%s' subscribes topics only with child subscribers.", nodelet::Nodelet::getName().c_str());
-    }
-  }
-
-  void Nodelet::connectionCallback(const ros::SingleSubscriberPublisher& pub)
-  {
-    if (verbose_connection_) {
-      NODELET_INFO("New connection or disconnection is detected");
-    }
-    if (!always_subscribe_) {
-      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 (!ever_subscribed_) {
-            ever_subscribed_ = true;
-          }
-          if (connection_status_ != SUBSCRIBED) {
-            if (verbose_connection_) {
-              NODELET_INFO("Subscribe input topics");
-            }
-            subscribe();
-            connection_status_ = SUBSCRIBED;
-          }
-          return;
-        }
-      }
-      if (connection_status_ == SUBSCRIBED) {
-        if (verbose_connection_) {
-          NODELET_INFO("Unsubscribe input topics");
-        }
-        unsubscribe();
-        connection_status_ = NOT_SUBSCRIBED;
-      }
-    }
-  }
-  
-  void Nodelet::imageConnectionCallback(
-    const image_transport::SingleSubscriberPublisher& pub)
-  {
-    if (verbose_connection_) {
-      NODELET_INFO("New image connection or disconnection is detected");
-    }
-    if (!always_subscribe_) {
-      boost::mutex::scoped_lock lock(connection_mutex_);
-      for (size_t i = 0; i < image_publishers_.size(); i++) {
-        image_transport::Publisher pub = image_publishers_[i];
-        if (pub.getNumSubscribers() > 0) {
-          if (!ever_subscribed_) {
-            ever_subscribed_ = true;
-          }
-          if (connection_status_ != SUBSCRIBED) {
-            if (verbose_connection_) {
-              NODELET_INFO("Subscribe input topics");
-            }
-            subscribe();
-            connection_status_ = SUBSCRIBED;
-          }
-          return;
-        }
-      }
-      if (connection_status_ == SUBSCRIBED) {
-        if (verbose_connection_) {
-          NODELET_INFO("Unsubscribe input topics");
-        }
-        unsubscribe();
-        connection_status_ = NOT_SUBSCRIBED;
-      }
-    }
-  }
-
-  void Nodelet::cameraConnectionCallback(
-    const image_transport::SingleSubscriberPublisher& pub)
-  {
-    cameraConnectionBaseCallback();
-  }
-
-  void Nodelet::cameraInfoConnectionCallback(
-    const ros::SingleSubscriberPublisher& pub)
-  {
-    cameraConnectionBaseCallback();
-  }
-
-  void Nodelet::cameraConnectionBaseCallback()
-  {
-    if (verbose_connection_) {
-      NODELET_INFO("New image connection or disconnection is detected");
-    }
-    if (!always_subscribe_) {
-      boost::mutex::scoped_lock lock(connection_mutex_);
-      for (size_t i = 0; i < camera_publishers_.size(); i++) {
-        image_transport::CameraPublisher pub = camera_publishers_[i];
-        if (pub.getNumSubscribers() > 0) {
-          if (!ever_subscribed_) {
-            ever_subscribed_ = true;
-          }
-          if (connection_status_ != SUBSCRIBED) {
-            if (verbose_connection_) {
-              NODELET_INFO("Subscribe input topics");
-            }
-            subscribe();
-            connection_status_ = SUBSCRIBED;
-          }
-          return;
-        }
-      }
-      if (connection_status_ == SUBSCRIBED) {
-        if (verbose_connection_) {
-          NODELET_INFO("Unsubscribe input topics");
-        }
-        unsubscribe();
-        connection_status_ = NOT_SUBSCRIBED;
-      }
-    }
-  }
-}
diff --git a/opencv_apps/src/nodelet/people_detect_nodelet.cpp b/opencv_apps/src/nodelet/people_detect_nodelet.cpp
index 7eae5e2..e6c7ae7 100644
--- a/opencv_apps/src/nodelet/people_detect_nodelet.cpp
+++ b/opencv_apps/src/nodelet/people_detect_nodelet.cpp
@@ -39,7 +39,7 @@
  */
 
 #include <ros/ros.h>
-#include "opencv_apps/nodelet.h"
+#include <nodelet/nodelet.h>
 #include <image_transport/image_transport.h>
 #include <cv_bridge/cv_bridge.h>
 
@@ -53,7 +53,7 @@
 #include "opencv_apps/RectArrayStamped.h"
 
 namespace people_detect {
-class PeopleDetectNodelet : public opencv_apps::Nodelet
+class PeopleDetectNodelet : public nodelet::Nodelet
 {
   image_transport::Publisher img_pub_;
   image_transport::Subscriber img_sub_;
@@ -61,11 +61,13 @@ class PeopleDetectNodelet : public opencv_apps::Nodelet
   ros::Publisher msg_pub_;
 
   boost::shared_ptr<image_transport::ImageTransport> it_;
+  ros::NodeHandle nh_, local_nh_;
 
   people_detect::PeopleDetectConfig config_;
   dynamic_reconfigure::Server<people_detect::PeopleDetectConfig> srv;
 
   bool debug_view_;
+  int subscriber_count_;
   ros::Time prev_stamp_;
 
   std::string window_name_;
@@ -76,6 +78,11 @@ class PeopleDetectNodelet : public opencv_apps::Nodelet
   void reconfigureCallback(people_detect::PeopleDetectConfig &new_config, uint32_t level)
   {
     config_ = new_config;
+    if (subscriber_count_)
+    { // @todo Could do this without an interruption at some point.
+      unsubscribe();
+      subscribe();
+    }
   }
 
   const std::string &frameWithDefault(const std::string &frame, const std::string &image_frame)
@@ -189,30 +196,65 @@ class PeopleDetectNodelet : public opencv_apps::Nodelet
     cam_sub_.shutdown();
   }
 
+  void img_connectCb(const image_transport::SingleSubscriberPublisher& ssp)
+  {
+    if (subscriber_count_++ == 0) {
+      subscribe();
+    }
+  }
+
+  void img_disconnectCb(const image_transport::SingleSubscriberPublisher&)
+  {
+    subscriber_count_--;
+    if (subscriber_count_ == 0) {
+      unsubscribe();
+    }
+  }
+
+  void msg_connectCb(const ros::SingleSubscriberPublisher& ssp)
+  {
+    if (subscriber_count_++ == 0) {
+      subscribe();
+    }
+  }
+
+  void msg_disconnectCb(const ros::SingleSubscriberPublisher&)
+  {
+    subscriber_count_--;
+    if (subscriber_count_ == 0) {
+      unsubscribe();
+    }
+  }
+
 public:
   virtual void onInit()
   {
-    Nodelet::onInit();
-    it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
+    nh_ = getNodeHandle();
+    it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(nh_));
+    local_nh_ = ros::NodeHandle("~");
 
-    pnh_->param("debug_view", debug_view_, false);
-    if (debug_view_) {
-      always_subscribe_ = true;
-    }
+    local_nh_.param("debug_view", debug_view_, false);
+    subscriber_count_ = 0;
     prev_stamp_ = ros::Time(0, 0);
 
     window_name_ = "people detector";
 
+    image_transport::SubscriberStatusCallback img_connect_cb    = boost::bind(&PeopleDetectNodelet::img_connectCb, this, _1);
+    image_transport::SubscriberStatusCallback img_disconnect_cb = boost::bind(&PeopleDetectNodelet::img_disconnectCb, this, _1);
+    ros::SubscriberStatusCallback msg_connect_cb    = boost::bind(&PeopleDetectNodelet::msg_connectCb, this, _1);
+    ros::SubscriberStatusCallback msg_disconnect_cb = boost::bind(&PeopleDetectNodelet::msg_disconnectCb, this, _1);
+    img_pub_ = image_transport::ImageTransport(local_nh_).advertise("image", 1, img_connect_cb, img_disconnect_cb);
+    msg_pub_ = local_nh_.advertise<opencv_apps::RectArrayStamped>("found", 1, msg_connect_cb, msg_disconnect_cb);
+        
+    hog_.setSVMDetector(cv::HOGDescriptor::getDefaultPeopleDetector());
+
+    if( debug_view_ ) {
+      subscriber_count_++;
+    }
+
     dynamic_reconfigure::Server<people_detect::PeopleDetectConfig>::CallbackType f =
       boost::bind(&PeopleDetectNodelet::reconfigureCallback, this, _1, _2);
     srv.setCallback(f);
-
-    hog_.setSVMDetector(cv::HOGDescriptor::getDefaultPeopleDetector());
-    
-    img_pub_ = advertiseImage(*pnh_, "image", 1);
-    msg_pub_ = advertise<opencv_apps::RectArrayStamped>(*pnh_, "found", 1);
-
-    onInitPostProcess();
   }
 };
 bool PeopleDetectNodelet::need_config_update_ = false;
diff --git a/opencv_apps/src/nodelet/phase_corr_nodelet.cpp b/opencv_apps/src/nodelet/phase_corr_nodelet.cpp
index 8b37f1b..00ae1af 100644
--- a/opencv_apps/src/nodelet/phase_corr_nodelet.cpp
+++ b/opencv_apps/src/nodelet/phase_corr_nodelet.cpp
@@ -35,7 +35,7 @@
 // https://github.com/Itseez/opencv/blob/master/samples/cpp/phase_corr.cpp
 
 #include <ros/ros.h>
-#include "opencv_apps/nodelet.h"
+#include <nodelet/nodelet.h>
 #include <image_transport/image_transport.h>
 #include <cv_bridge/cv_bridge.h>
 
@@ -47,7 +47,7 @@
 #include "opencv_apps/Point2DStamped.h"
 
 namespace phase_corr {
-class PhaseCorrNodelet : public opencv_apps::Nodelet
+class PhaseCorrNodelet : public nodelet::Nodelet
 {
   image_transport::Publisher img_pub_;
   image_transport::Subscriber img_sub_;
@@ -55,11 +55,13 @@ class PhaseCorrNodelet : public opencv_apps::Nodelet
   ros::Publisher msg_pub_;
 
   boost::shared_ptr<image_transport::ImageTransport> it_;
+  ros::NodeHandle nh_, local_nh_;
 
   phase_corr::PhaseCorrConfig config_;
   dynamic_reconfigure::Server<phase_corr::PhaseCorrConfig> srv;
 
   bool debug_view_;
+  int subscriber_count_;
   ros::Time prev_stamp_;
 
   cv::Mat curr, prev, curr64f, prev64f, hann;
@@ -70,6 +72,11 @@ class PhaseCorrNodelet : public opencv_apps::Nodelet
   void reconfigureCallback(phase_corr::PhaseCorrConfig &new_config, uint32_t level)
   {
     config_ = new_config;
+    if (subscriber_count_)
+    { // @todo Could do this without an interruption at some point.
+      unsubscribe();
+      subscribe();
+    }
   }
 
   const std::string &frameWithDefault(const std::string &frame, const std::string &image_frame)
@@ -188,28 +195,63 @@ class PhaseCorrNodelet : public opencv_apps::Nodelet
     cam_sub_.shutdown();
   }
 
+  void img_connectCb(const image_transport::SingleSubscriberPublisher& ssp)
+  {
+    if (subscriber_count_++ == 0) {
+      subscribe();
+    }
+  }
+
+  void img_disconnectCb(const image_transport::SingleSubscriberPublisher&)
+  {
+    subscriber_count_--;
+    if (subscriber_count_ == 0) {
+      unsubscribe();
+    }
+  }
+
+  void msg_connectCb(const ros::SingleSubscriberPublisher& ssp)
+  {
+    if (subscriber_count_++ == 0) {
+      subscribe();
+    }
+  }
+
+  void msg_disconnectCb(const ros::SingleSubscriberPublisher&)
+  {
+    subscriber_count_--;
+    if (subscriber_count_ == 0) {
+      unsubscribe();
+    }
+  }
+
 public:
   virtual void onInit()
   {
-    Nodelet::onInit();
-    it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
+    nh_ = getNodeHandle();
+    it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(nh_));
+    local_nh_ = ros::NodeHandle("~");
 
-    pnh_->param("debug_view", debug_view_, false);
-    if (debug_view_) {
-      always_subscribe_ = true;
-    }
+    local_nh_.param("debug_view", debug_view_, false);
+    subscriber_count_ = 0;
     prev_stamp_ = ros::Time(0, 0);
 
     window_name_ = "phase shift";
-    
+
+    image_transport::SubscriberStatusCallback img_connect_cb    = boost::bind(&PhaseCorrNodelet::img_connectCb, this, _1);
+    image_transport::SubscriberStatusCallback img_disconnect_cb = boost::bind(&PhaseCorrNodelet::img_disconnectCb, this, _1);
+    ros::SubscriberStatusCallback msg_connect_cb    = boost::bind(&PhaseCorrNodelet::msg_connectCb, this, _1);
+    ros::SubscriberStatusCallback msg_disconnect_cb = boost::bind(&PhaseCorrNodelet::msg_disconnectCb, this, _1);
+    img_pub_ = image_transport::ImageTransport(local_nh_).advertise("image", 1, img_connect_cb, img_disconnect_cb);
+    msg_pub_ = local_nh_.advertise<opencv_apps::Point2DStamped>("shift", 1, msg_connect_cb, msg_disconnect_cb);
+
+    if( debug_view_ ) {
+      subscriber_count_++;
+    }
+
     dynamic_reconfigure::Server<phase_corr::PhaseCorrConfig>::CallbackType f =
       boost::bind(&PhaseCorrNodelet::reconfigureCallback, this, _1, _2);
     srv.setCallback(f);
-
-    img_pub_ = advertiseImage(*pnh_, "image", 1);
-    msg_pub_ = advertise<opencv_apps::Point2DStamped>(*pnh_, "shift", 1);
-
-    onInitPostProcess();
   }
 };
 bool PhaseCorrNodelet::need_config_update_ = false;
diff --git a/opencv_apps/src/nodelet/segment_objects_nodelet.cpp b/opencv_apps/src/nodelet/segment_objects_nodelet.cpp
index 05cf6f5..6c1012b 100644
--- a/opencv_apps/src/nodelet/segment_objects_nodelet.cpp
+++ b/opencv_apps/src/nodelet/segment_objects_nodelet.cpp
@@ -38,7 +38,7 @@
  */
 
 #include <ros/ros.h>
-#include "opencv_apps/nodelet.h"
+#include <nodelet/nodelet.h>
 #include <image_transport/image_transport.h>
 #include <cv_bridge/cv_bridge.h>
 
@@ -55,7 +55,7 @@
 #include "opencv_apps/ContourArrayStamped.h"
 
 namespace segment_objects {
-class SegmentObjectsNodelet : public opencv_apps::Nodelet
+class SegmentObjectsNodelet : public nodelet::Nodelet
 {
   image_transport::Publisher img_pub_;
   image_transport::Subscriber img_sub_;
@@ -64,11 +64,13 @@ class SegmentObjectsNodelet : public opencv_apps::Nodelet
   ros::ServiceServer update_bg_model_service_;
 
   boost::shared_ptr<image_transport::ImageTransport> it_;
+  ros::NodeHandle nh_, local_nh_;
 
   segment_objects::SegmentObjectsConfig config_;
   dynamic_reconfigure::Server<segment_objects::SegmentObjectsConfig> srv;
 
   bool debug_view_;
+  int subscriber_count_;
   ros::Time prev_stamp_;
 
   std::string window_name_;
@@ -84,6 +86,11 @@ class SegmentObjectsNodelet : public opencv_apps::Nodelet
   void reconfigureCallback(segment_objects::SegmentObjectsConfig &new_config, uint32_t level)
   {
     config_ = new_config;
+    if (subscriber_count_)
+    { // @todo Could do this without an interruption at some point.
+      unsubscribe();
+      subscribe();
+    }
   }
 
   const std::string &frameWithDefault(const std::string &frame, const std::string &image_frame)
@@ -236,16 +243,45 @@ class SegmentObjectsNodelet : public opencv_apps::Nodelet
     cam_sub_.shutdown();
   }
 
+  void img_connectCb(const image_transport::SingleSubscriberPublisher& ssp)
+  {
+    if (subscriber_count_++ == 0) {
+      subscribe();
+    }
+  }
+
+  void img_disconnectCb(const image_transport::SingleSubscriberPublisher&)
+  {
+    subscriber_count_--;
+    if (subscriber_count_ == 0) {
+      unsubscribe();
+    }
+  }
+
+  void msg_connectCb(const ros::SingleSubscriberPublisher& ssp)
+  {
+    if (subscriber_count_++ == 0) {
+      subscribe();
+    }
+  }
+
+  void msg_disconnectCb(const ros::SingleSubscriberPublisher&)
+  {
+    subscriber_count_--;
+    if (subscriber_count_ == 0) {
+      unsubscribe();
+    }
+  }
+
 public:
   virtual void onInit()
   {
-    Nodelet::onInit();
-    it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
+    nh_ = getNodeHandle();
+    it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(nh_));
+    local_nh_ = ros::NodeHandle("~");
 
-    pnh_->param("debug_view", debug_view_, false);
-    if (debug_view_) {
-      always_subscribe_ = true;
-    }
+    local_nh_.param("debug_view", debug_view_, false);
+    subscriber_count_ = 0;
     prev_stamp_ = ros::Time(0, 0);
 
     window_name_ = "segmented";
@@ -257,16 +293,22 @@ public:
     bgsubtractor.set("noiseSigma", 10);
 #endif
 
+    image_transport::SubscriberStatusCallback img_connect_cb    = boost::bind(&SegmentObjectsNodelet::img_connectCb, this, _1);
+    image_transport::SubscriberStatusCallback img_disconnect_cb = boost::bind(&SegmentObjectsNodelet::img_disconnectCb, this, _1);
+    ros::SubscriberStatusCallback msg_connect_cb    = boost::bind(&SegmentObjectsNodelet::msg_connectCb, this, _1);
+    ros::SubscriberStatusCallback msg_disconnect_cb = boost::bind(&SegmentObjectsNodelet::msg_disconnectCb, this, _1);
+    img_pub_ = image_transport::ImageTransport(local_nh_).advertise("image", 1, img_connect_cb, img_disconnect_cb);
+    msg_pub_ = local_nh_.advertise<opencv_apps::ContourArrayStamped>("contours", 1, msg_connect_cb, msg_disconnect_cb);
+    area_pub_ = local_nh_.advertise<std_msgs::Float64>("area", 1, msg_connect_cb, msg_disconnect_cb);
+    update_bg_model_service_ = local_nh_.advertiseService("update_bg_model", &SegmentObjectsNodelet::update_bg_model_cb, this);
+        
+    if( debug_view_ ) {
+      subscriber_count_++;
+    }
+
     dynamic_reconfigure::Server<segment_objects::SegmentObjectsConfig>::CallbackType f =
       boost::bind(&SegmentObjectsNodelet::reconfigureCallback, this, _1, _2);
     srv.setCallback(f);
-    
-    img_pub_ = advertiseImage(*pnh_, "image", 1);
-    msg_pub_ = advertise<opencv_apps::ContourArrayStamped>(*pnh_, "contours", 1);
-    area_pub_ = advertise<std_msgs::Float64>(*pnh_, "area", 1);
-    update_bg_model_service_ = pnh_->advertiseService("update_bg_model", &SegmentObjectsNodelet::update_bg_model_cb, this);
-
-    onInitPostProcess();
   }
 };
 bool SegmentObjectsNodelet::need_config_update_ = false;
diff --git a/opencv_apps/src/nodelet/simple_flow_nodelet.cpp b/opencv_apps/src/nodelet/simple_flow_nodelet.cpp
index 9b683cc..d454b2f 100644
--- a/opencv_apps/src/nodelet/simple_flow_nodelet.cpp
+++ b/opencv_apps/src/nodelet/simple_flow_nodelet.cpp
@@ -38,7 +38,7 @@
  */
 
 #include <ros/ros.h>
-#include "opencv_apps/nodelet.h"
+#include <nodelet/nodelet.h>
 #include <image_transport/image_transport.h>
 #include <cv_bridge/cv_bridge.h>
 
@@ -54,7 +54,7 @@
 #include "opencv_apps/FlowArrayStamped.h"
 
 namespace simple_flow {
-class SimpleFlowNodelet : public opencv_apps::Nodelet
+class SimpleFlowNodelet : public nodelet::Nodelet
 {
   image_transport::Publisher img_pub_;
   image_transport::Subscriber img_sub_;
@@ -62,6 +62,7 @@ class SimpleFlowNodelet : public opencv_apps::Nodelet
   ros::Publisher msg_pub_;
 
   boost::shared_ptr<image_transport::ImageTransport> it_;
+  ros::NodeHandle nh_, local_nh_;
 
   simple_flow::SimpleFlowConfig config_;
   dynamic_reconfigure::Server<simple_flow::SimpleFlowConfig> srv;
@@ -80,6 +81,11 @@ class SimpleFlowNodelet : public opencv_apps::Nodelet
   {
     config_ = new_config;
     scale_ = config_.scale;
+    if (subscriber_count_)
+    { // @todo Could do this without an interruption at some point.
+      unsubscribe();
+      subscribe();
+    }
   }
 
   const std::string &frameWithDefault(const std::string &frame, const std::string &image_frame)
@@ -224,29 +230,64 @@ class SimpleFlowNodelet : public opencv_apps::Nodelet
     cam_sub_.shutdown();
   }
 
+  void img_connectCb(const image_transport::SingleSubscriberPublisher& ssp)
+  {
+    if (subscriber_count_++ == 0) {
+      subscribe();
+    }
+  }
+
+  void img_disconnectCb(const image_transport::SingleSubscriberPublisher&)
+  {
+    subscriber_count_--;
+    if (subscriber_count_ == 0) {
+      unsubscribe();
+    }
+  }
+
+  void msg_connectCb(const ros::SingleSubscriberPublisher& ssp)
+  {
+    if (subscriber_count_++ == 0) {
+      subscribe();
+    }
+  }
+
+  void msg_disconnectCb(const ros::SingleSubscriberPublisher&)
+  {
+    subscriber_count_--;
+    if (subscriber_count_ == 0) {
+      unsubscribe();
+    }
+  }
+
 public:
   virtual void onInit()
   {
-    Nodelet::onInit();
-    it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
+    nh_ = getNodeHandle();
+    it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(nh_));
+    local_nh_ = ros::NodeHandle("~");
 
-    pnh_->param("debug_view", debug_view_, false);
-    if (debug_view_) {
-      always_subscribe_ = true;
-    }
+    local_nh_.param("debug_view", debug_view_, false);
+    subscriber_count_ = 0;
     prev_stamp_ = ros::Time(0, 0);
 
     window_name_ = "simpleflow_demo";
     scale_ = 4.0;
 
+    image_transport::SubscriberStatusCallback img_connect_cb    = boost::bind(&SimpleFlowNodelet::img_connectCb, this, _1);
+    image_transport::SubscriberStatusCallback img_disconnect_cb = boost::bind(&SimpleFlowNodelet::img_disconnectCb, this, _1);
+    ros::SubscriberStatusCallback msg_connect_cb    = boost::bind(&SimpleFlowNodelet::msg_connectCb, this, _1);
+    ros::SubscriberStatusCallback msg_disconnect_cb = boost::bind(&SimpleFlowNodelet::msg_disconnectCb, this, _1);
+    img_pub_ = image_transport::ImageTransport(local_nh_).advertise("image", 1, img_connect_cb, img_disconnect_cb);
+    msg_pub_ = local_nh_.advertise<opencv_apps::FlowArrayStamped>("flows", 1, msg_connect_cb, msg_disconnect_cb);
+        
+    if( debug_view_ ) {
+      subscriber_count_++;
+    }
+
     dynamic_reconfigure::Server<simple_flow::SimpleFlowConfig>::CallbackType f =
       boost::bind(&SimpleFlowNodelet::reconfigureCallback, this, _1, _2);
     srv.setCallback(f);
-    
-    img_pub_ = advertiseImage(*pnh_, "image", 1);
-    msg_pub_ = advertise<opencv_apps::FlowArrayStamped>(*pnh_, "flows", 1);
-
-    onInitPostProcess();
   }
 };
 bool SimpleFlowNodelet::need_config_update_ = false;
diff --git a/opencv_apps/src/nodelet/watershed_segmentation_nodelet.cpp b/opencv_apps/src/nodelet/watershed_segmentation_nodelet.cpp
index 4c528a9..fc604b5 100644
--- a/opencv_apps/src/nodelet/watershed_segmentation_nodelet.cpp
+++ b/opencv_apps/src/nodelet/watershed_segmentation_nodelet.cpp
@@ -38,7 +38,7 @@
  */
 
 #include <ros/ros.h>
-#include "opencv_apps/nodelet.h"
+#include <nodelet/nodelet.h>
 #include <image_transport/image_transport.h>
 #include <cv_bridge/cv_bridge.h>
 
@@ -53,7 +53,7 @@
 #include "opencv_apps/Point2DArray.h"
 
 namespace watershed_segmentation {
-class WatershedSegmentationNodelet : public opencv_apps::Nodelet
+class WatershedSegmentationNodelet : public nodelet::Nodelet
 {
   image_transport::Publisher img_pub_;
   image_transport::Subscriber img_sub_;
@@ -62,11 +62,13 @@ class WatershedSegmentationNodelet : public opencv_apps::Nodelet
   ros::Subscriber add_seed_points_sub_;
 
   boost::shared_ptr<image_transport::ImageTransport> it_;
+  ros::NodeHandle nh_, local_nh_;
 
   watershed_segmentation::WatershedSegmentationConfig config_;
   dynamic_reconfigure::Server<watershed_segmentation::WatershedSegmentationConfig> srv;
 
   bool debug_view_;
+  int subscriber_count_;
   ros::Time prev_stamp_;
 
   std::string window_name_, segment_name_;
@@ -92,6 +94,11 @@ class WatershedSegmentationNodelet : public opencv_apps::Nodelet
   void reconfigureCallback(watershed_segmentation::WatershedSegmentationConfig &new_config, uint32_t level)
   {
     config_ = new_config;
+    if (subscriber_count_)
+    { // @todo Could do this without an interruption at some point.
+      unsubscribe();
+      subscribe();
+    }
   }
 
   const std::string &frameWithDefault(const std::string &frame, const std::string &image_frame)
@@ -290,16 +297,45 @@ class WatershedSegmentationNodelet : public opencv_apps::Nodelet
     cam_sub_.shutdown();
   }
 
+  void img_connectCb(const image_transport::SingleSubscriberPublisher& ssp)
+  {
+    if (subscriber_count_++ == 0) {
+      subscribe();
+    }
+  }
+
+  void img_disconnectCb(const image_transport::SingleSubscriberPublisher&)
+  {
+    subscriber_count_--;
+    if (subscriber_count_ == 0) {
+      unsubscribe();
+    }
+  }
+
+  void msg_connectCb(const ros::SingleSubscriberPublisher& ssp)
+  {
+    if (subscriber_count_++ == 0) {
+      subscribe();
+    }
+  }
+
+  void msg_disconnectCb(const ros::SingleSubscriberPublisher&)
+  {
+    subscriber_count_--;
+    if (subscriber_count_ == 0) {
+      unsubscribe();
+    }
+  }
+
 public:
   virtual void onInit()
   {
-    Nodelet::onInit();
-    it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
+    nh_ = getNodeHandle();
+    it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(nh_));
+    local_nh_ = ros::NodeHandle("~");
 
-    pnh_->param("debug_view", debug_view_, false);
-    if (debug_view_) {
-      always_subscribe_ = true;
-    }
+    local_nh_.param("debug_view", debug_view_, false);
+    subscriber_count_ = 0;
     prev_stamp_ = ros::Time(0, 0);
 
     window_name_ = "roughly mark the areas to segment on the image";
@@ -307,15 +343,22 @@ public:
     prevPt.x = -1;
     prevPt.y = -1;
 
+    image_transport::SubscriberStatusCallback img_connect_cb    = boost::bind(&WatershedSegmentationNodelet::img_connectCb, this, _1);
+    image_transport::SubscriberStatusCallback img_disconnect_cb = boost::bind(&WatershedSegmentationNodelet::img_disconnectCb, this, _1);
+    ros::SubscriberStatusCallback msg_connect_cb    = boost::bind(&WatershedSegmentationNodelet::msg_connectCb, this, _1);
+    ros::SubscriberStatusCallback msg_disconnect_cb = boost::bind(&WatershedSegmentationNodelet::msg_disconnectCb, this, _1);
+    img_pub_ = image_transport::ImageTransport(local_nh_).advertise("image", 1, img_connect_cb, img_disconnect_cb);
+    msg_pub_ = local_nh_.advertise<opencv_apps::ContourArrayStamped>("contours", 1, msg_connect_cb, msg_disconnect_cb);
+    add_seed_points_sub_ = local_nh_.subscribe("add_seed_points", 1, &WatershedSegmentationNodelet::add_seed_point_cb, this);
+        
+    if( debug_view_ ) {
+      subscriber_count_++;
+    }
+
     dynamic_reconfigure::Server<watershed_segmentation::WatershedSegmentationConfig>::CallbackType f =
       boost::bind(&WatershedSegmentationNodelet::reconfigureCallback, this, _1, _2);
     srv.setCallback(f);
 
-    add_seed_points_sub_ = pnh_->subscribe("add_seed_points", 1, &WatershedSegmentationNodelet::add_seed_point_cb, this);
-    img_pub_ = advertiseImage(*pnh_, "image", 1);
-    msg_pub_ = advertise<opencv_apps::ContourArrayStamped>(*pnh_, "contours", 1);
-    
-
     NODELET_INFO("This program demonstrates the famous watershed segmentation algorithm in OpenCV: watershed()");
     NODELET_INFO("Hot keys: ");
     NODELET_INFO("\tESC - quit the program");
@@ -323,8 +366,6 @@ public:
     NODELET_INFO("\tw or SPACE - run watershed segmentation algorithm");
     NODELET_INFO("\t\t(before running it, *roughly* mark the areas to segment on the image)");
     NODELET_INFO("\t  (before that, roughly outline several markers on the image)");
-
-    onInitPostProcess();
   }
 };
 bool WatershedSegmentationNodelet::need_config_update_ = false;
diff --git a/opencv_apps/test/test-hough_lines.test b/opencv_apps/test/test-hough_lines.test
index 27b611f..f5fc8b9 100644
--- a/opencv_apps/test/test-hough_lines.test
+++ b/opencv_apps/test/test-hough_lines.test
@@ -19,7 +19,7 @@
     <param name="standard_hough_lines_test/topic" value="standard_hough_lines/lines" />    <!-- opencv_apps/LineArrayStamped -->
     <test test-name="standard_hough_lines_test" pkg="rostest" type="hztest" name="standard_hough_lines_test" >
       <param name="hz" value="20" />
-      <param name="hzerror" value="19" />
+      <param name="hzerror" value="15" />
       <param name="test_duration" value="5.0" /> 
     </test>
 
@@ -35,7 +35,7 @@
     <param name="probabilistic_hough_lines_test/topic" value="probabilistic_hough_lines/lines" />    <!-- opencv_apps/LineArrayStamped -->
     <test test-name="probabilistic_hough_lines_test" pkg="rostest" type="hztest" name="probabilistic_hough_lines_test" >
       <param name="hz" value="20" />
-      <param name="hzerror" value="19" />
+      <param name="hzerror" value="15" />
       <param name="test_duration" value="5.0" /> 
     </test>
   </group>
diff --git a/opencv_apps/test/test-people_detect.test b/opencv_apps/test/test-people_detect.test
index 9ecb903..b8ad3a5 100644
--- a/opencv_apps/test/test-people_detect.test
+++ b/opencv_apps/test/test-people_detect.test
@@ -16,7 +16,7 @@
     <param name="people_detect_test/topic" value="people_detect/found" />    <!-- opencv_apps/RectArrayStamped -->
     <test test-name="people_detect_test" pkg="rostest" type="hztest" name="people_detect_test" >
       <param name="hz" value="15" />
-      <param name="hzerror" value="14.5" />
+      <param name="hzerror" value="14" />
       <param name="test_duration" value="5.0" /> 
     </test>
   </group>
diff --git a/opencv_apps/test/test-simple_flow.test b/opencv_apps/test/test-simple_flow.test
index e27ce9b..25b05ee 100644
--- a/opencv_apps/test/test-simple_flow.test
+++ b/opencv_apps/test/test-simple_flow.test
@@ -16,8 +16,8 @@
     </node>
     <param name="simple_flow_test/topic" value="simple_flow/flows" />    <!-- opencv_apps/FlowArrayStamped -->
     <test test-name="simple_flow_test" pkg="rostest" type="hztest" name="simple_flow_test" >
-      <param name="hz" value="5" />
-      <param name="hzerror" value="4.5" />
+      <param name="hz" value="15" />
+      <param name="hzerror" value="14" />
       <param name="test_duration" value="5.0" /> 
     </test>
   </group>
diff --git a/opencv_tests/CHANGELOG.rst b/opencv_tests/CHANGELOG.rst
index 886f98b..899ea96 100644
--- a/opencv_tests/CHANGELOG.rst
+++ b/opencv_tests/CHANGELOG.rst
@@ -2,12 +2,6 @@
 Changelog for package opencv_tests
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
-1.12.0 (2016-03-18)
--------------------
-
-1.11.12 (2016-03-10)
---------------------
-
 1.11.11 (2016-01-31)
 --------------------
 * fix a few warnings in doc jobs
diff --git a/opencv_tests/package.xml b/opencv_tests/package.xml
index b4b303a..4cc2841 100644
--- a/opencv_tests/package.xml
+++ b/opencv_tests/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>opencv_tests</name>
-  <version>1.12.0</version>
+  <version>1.11.11</version>
   <description>
     Tests the enumerants of the ROS Image message, and functionally tests the Python and C++ implementations of CvBridge.
   </description>
diff --git a/vision_opencv/CHANGELOG.rst b/vision_opencv/CHANGELOG.rst
index 35e5bce..a423932 100644
--- a/vision_opencv/CHANGELOG.rst
+++ b/vision_opencv/CHANGELOG.rst
@@ -2,14 +2,6 @@
 Changelog for package vision_opencv
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
-1.12.0 (2016-03-18)
--------------------
-* remove opencv_apps from vision_opencv
-* Contributors: Vincent Rabaud
-
-1.11.12 (2016-03-10)
---------------------
-
 1.11.11 (2016-01-31)
 --------------------
 
diff --git a/vision_opencv/package.xml b/vision_opencv/package.xml
index d822b3f..17c91db 100644
--- a/vision_opencv/package.xml
+++ b/vision_opencv/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>vision_opencv</name>
-  <version>1.12.0</version>
+  <version>1.11.11</version>
   <description>Packages for interfacing ROS with OpenCV, a library of programming functions for real time computer vision.</description>
   <author>Patrick Mihelich</author>
   <author>James Bowman</author>
@@ -13,8 +13,10 @@
 
   <buildtool_depend>catkin</buildtool_depend>
   
+  <!-- Old stack contents -->
   <run_depend>cv_bridge</run_depend>
   <run_depend>image_geometry</run_depend>
+  <run_depend>opencv_apps</run_depend>
   <export>
     <metapackage/>
   </export>

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



More information about the debian-science-commits mailing list