[ros-ros-comm] 01/06: New upstream version 1.12.3

Jochen Sprickerhof jspricke at moszumanska.debian.org
Mon Sep 19 08:42:32 UTC 2016


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

jspricke pushed a commit to annotated tag debian/1.12.3-1
in repository ros-ros-comm.

commit 31ea007e70b1b4b21482c64891b8a9a64407fcc5
Author: Jochen Sprickerhof <git at jochen.sprickerhof.de>
Date:   Mon Sep 19 08:57:45 2016 +0200

    New upstream version 1.12.3
---
 clients/roscpp/CHANGELOG.rst                       |   7 +
 clients/roscpp/include/ros/spinner.h               |   8 +-
 clients/roscpp/package.xml                         |   2 +-
 clients/roscpp/rosbuild/scripts/msg_gen.py         |   2 +-
 clients/roscpp/src/libros/connection.cpp           |   4 +
 clients/roscpp/src/libros/init.cpp                 |   1 +
 clients/roscpp/src/libros/param.cpp                |   7 +-
 clients/roscpp/src/libros/service_client_link.cpp  |   4 +
 clients/roscpp/src/libros/service_manager.cpp      |  14 +-
 clients/roscpp/src/libros/service_server_link.cpp  |   2 +
 clients/roscpp/src/libros/spinner.cpp              | 154 ++++++++---
 clients/roscpp/src/libros/subscription_queue.cpp   |   2 +-
 clients/roscpp/src/libros/this_node.cpp            |  77 ++++--
 clients/roscpp/src/libros/topic_manager.cpp        |   3 +
 .../roscpp/src/libros/transport_publisher_link.cpp |   4 +
 .../src/libros/transport_subscriber_link.cpp       |   1 +
 clients/rospy/CHANGELOG.rst                        |   6 +
 clients/rospy/package.xml                          |   2 +-
 clients/rospy/src/rospy/client.py                  |   5 +-
 clients/rospy/src/rospy/timer.py                   |   2 +-
 clients/rospy/test_nodes/talker.py                 |   2 +-
 ros_comm/CHANGELOG.rst                             |   3 +
 ros_comm/package.xml                               |   2 +-
 test/test_rosbag/CMakeLists.txt                    |   2 +-
 test/test_rosbag/package.xml                       |   2 +-
 test/test_rosbag_storage/package.xml               |   2 +-
 test/test_roscpp/package.xml                       |   2 +-
 test/test_roscpp/test/CMakeLists.txt               |  18 +-
 test/test_roscpp/test/launch/spinners.xml          |   4 +
 test/test_roscpp/test/src/CMakeLists.txt           |   6 +
 test/test_roscpp/test/src/latching_publisher.cpp   |   2 +-
 .../test/{test_spinners.cpp => src/spinners.cpp}   | 102 +++++---
 test/test_roscpp/test/src/subscribe_star.cpp       |   2 +-
 test/test_roscpp/test/src/timer_callbacks.cpp      |   2 +-
 test/test_roscpp/test/src/wait_for_message.cpp     |   2 +-
 test/test_roscpp/test/test_names.cpp               |   8 +
 .../test_serialization/src/serialization.cpp       |   2 +-
 test/test_rosgraph/package.xml                     |   2 +-
 test/test_roslaunch/package.xml                    |   2 +-
 test/test_roslib_comm/package.xml                  |   2 +-
 test/test_rosmaster/package.xml                    |   2 +-
 test/test_rosparam/package.xml                     |   2 +-
 test/test_rospy/package.xml                        |   2 +-
 test/test_rospy/test/unit/test_rospy_client.py     |  14 +
 test/test_rosservice/package.xml                   |   2 +-
 test/test_rostopic/package.xml                     |   2 +-
 tools/rosbag/CHANGELOG.rst                         |   7 +
 tools/rosbag/include/rosbag/recorder.h             |   6 +-
 tools/rosbag/package.xml                           |   2 +-
 tools/rosbag/src/record.cpp                        |  16 +-
 tools/rosbag/src/recorder.cpp                      |  23 +-
 tools/rosbag/src/rosbag/rosbag_main.py             |   5 +-
 tools/rosbag_storage/CHANGELOG.rst                 |   4 +
 tools/rosbag_storage/include/rosbag/bag.h          |   2 +-
 tools/rosbag_storage/package.xml                   |   2 +-
 tools/rosconsole/CHANGELOG.rst                     |   3 +
 tools/rosconsole/package.xml                       |   2 +-
 tools/rosgraph/CHANGELOG.rst                       |   6 +
 tools/rosgraph/package.xml                         |   2 +-
 tools/rosgraph/src/rosgraph/impl/graph.py          |   3 +
 tools/rosgraph/src/rosgraph/network.py             |   3 +-
 tools/rosgraph/src/rosgraph/roslogging.py          |   6 +-
 tools/roslaunch/CHANGELOG.rst                      |   7 +
 tools/roslaunch/package.xml                        |   4 +-
 tools/roslaunch/scripts/roslaunch-check            |  31 ++-
 tools/roslaunch/src/roslaunch/depends.py           |  23 +-
 tools/roslaunch/src/roslaunch/loader.py            |   4 +-
 tools/roslaunch/src/roslaunch/rlutil.py            |   5 +-
 tools/rosmaster/CHANGELOG.rst                      |   3 +
 tools/rosmaster/package.xml                        |   2 +-
 tools/rosmsg/CHANGELOG.rst                         |   4 +
 tools/rosmsg/CMakeLists.txt                        |   4 +
 tools/rosmsg/package.xml                           |   4 +-
 tools/rosmsg/test/RosmsgC_raw.txt                  |   4 +
 tools/rosmsg/test/msg/RosmsgB.msg                  |   2 +-
 tools/rosmsg/test/msg/RosmsgC.msg                  |   2 -
 tools/rosmsg/test/srv/RossrvB.srv                  |   4 +-
 tools/rosmsg/test/test_rosmsg.py                   |  58 +++--
 tools/rosmsg/test/test_rosmsg_command_line.py      |  54 ++--
 tools/rosmsg/test/test_rosmsgproto.py              |  15 ++
 tools/rosmsg/test/test_rosmsgproto_geometry.py     |  89 -------
 tools/rosnode/CHANGELOG.rst                        |   3 +
 tools/rosnode/package.xml                          |   2 +-
 tools/rosout/CHANGELOG.rst                         |   3 +
 tools/rosout/package.xml                           |   2 +-
 tools/rosparam/CHANGELOG.rst                       |   3 +
 tools/rosparam/package.xml                         |   2 +-
 tools/rosservice/CHANGELOG.rst                     |   4 +
 tools/rosservice/package.xml                       |   2 +-
 tools/rosservice/src/rosservice/__init__.py        |   6 +-
 tools/rostest/CHANGELOG.rst                        |   5 +
 tools/rostest/CMakeLists.txt                       |   7 +-
 tools/rostest/cmake/rostest-extras.cmake.em        |   2 +-
 tools/rostest/nodes/paramtest                      | 110 ++++++++
 tools/rostest/nodes/publishtest                    | 149 +++++++++++
 tools/rostest/package.xml                          |   2 +-
 tools/rostest/test/hztest.test                     |  13 +
 .../talker.py => tools/rostest/test/just_advertise |  32 ++-
 tools/rostest/test/param.test                      |  30 +++
 tools/rostest/test/publishtest.test                |  35 +++
 tools/rostopic/CHANGELOG.rst                       |   7 +
 tools/rostopic/package.xml                         |   2 +-
 tools/rostopic/src/rostopic/__init__.py            | 287 ++++++++++++++++-----
 .../test/check_rostopic_command_line_online.py     |   4 +
 tools/rostopic/test/test_rostopic.py               |   4 +
 tools/topic_tools/CHANGELOG.rst                    |   4 +
 tools/topic_tools/CMakeLists.txt                   |   2 +
 tools/topic_tools/package.xml                      |   2 +-
 tools/topic_tools/python/topic_tools/__init__.py   |  79 ++++++
 tools/topic_tools/sample/simple_lazy_transport.py  |  29 +++
 tools/topic_tools/setup.py                         |  10 +
 tools/topic_tools/test/lazy_transport.test         |  28 ++
 tools/topic_tools/test/test_lazy_transport.py      |  64 +++++
 utilities/message_filters/CHANGELOG.rst            |   4 +
 utilities/message_filters/package.xml              |   2 +-
 .../src/message_filters/__init__.py                |  36 ++-
 utilities/roslz4/CHANGELOG.rst                     |   4 +
 utilities/roslz4/CMakeLists.txt                    |   3 +-
 utilities/roslz4/package.xml                       |   2 +-
 utilities/roswtf/CHANGELOG.rst                     |   3 +
 utilities/roswtf/package.xml                       |   2 +-
 .../test/check_roswtf_command_line_online.py       |   6 +
 .../test/test_roswtf_command_line_offline.py       |   6 +
 utilities/xmlrpcpp/CHANGELOG.rst                   |   3 +
 utilities/xmlrpcpp/package.xml                     |   2 +-
 125 files changed, 1482 insertions(+), 436 deletions(-)

diff --git a/clients/roscpp/CHANGELOG.rst b/clients/roscpp/CHANGELOG.rst
index b4b6038..307e067 100644
--- a/clients/roscpp/CHANGELOG.rst
+++ b/clients/roscpp/CHANGELOG.rst
@@ -2,6 +2,13 @@
 Changelog for package roscpp
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.12.3 (2016-09-17)
+-------------------
+* fix multi-threaded spinning (`#867 <https://github.com/ros/ros_comm/pull/867>`_)
+* fix static destruction order (`#871 <https://github.com/ros/ros_comm/pull/871>`_)
+* throw exception on ros::init with empty node name (`#894 <https://github.com/ros/ros_comm/pull/894>`_)
+* improve debug message when queue is full (`#818 <https://github.com/ros/ros_comm/issues/818>`_)
+
 1.12.2 (2016-06-03)
 -------------------
 * improve stacktrace for exceptions thrown in callbacks (`#811 <https://github.com/ros/ros_comm/pull/811>`_)
diff --git a/clients/roscpp/include/ros/spinner.h b/clients/roscpp/include/ros/spinner.h
index 5972049..d09f0a0 100644
--- a/clients/roscpp/include/ros/spinner.h
+++ b/clients/roscpp/include/ros/spinner.h
@@ -109,9 +109,13 @@ public:
 
 
   /**
-   * \brief Check if the spinner can be started. A spinner can't be started if
-   * another spinner is already running.
+   * \brief Check if the spinner can be started. The spinner shouldn't be started if
+   * another single-threaded spinner is already operating on the callback queue.
+   *
+   * This function is not necessary anymore. start() will always try to start spinning
+   * and throw a std::runtime_error if it failed.
    */
+  // TODO: deprecate in L-turtle
   bool canStart();
   /**
    * \brief Start this spinner spinning asynchronously
diff --git a/clients/roscpp/package.xml b/clients/roscpp/package.xml
index f1815c0..ea4656e 100644
--- a/clients/roscpp/package.xml
+++ b/clients/roscpp/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>roscpp</name>
-  <version>1.12.2</version>
+  <version>1.12.3</version>
   <description>
     roscpp is a C++ implementation of ROS. It provides
     a <a href="http://www.ros.org/wiki/Client%20Libraries">client
diff --git a/clients/roscpp/rosbuild/scripts/msg_gen.py b/clients/roscpp/rosbuild/scripts/msg_gen.py
index b3bf8a9..599cc02 100755
--- a/clients/roscpp/rosbuild/scripts/msg_gen.py
+++ b/clients/roscpp/rosbuild/scripts/msg_gen.py
@@ -670,7 +670,7 @@ def write_serialization(s, spec, cpp_name_prefix):
         s.write('    stream.next(m.%s);\n'%(field.name))
     s.write('  }\n\n')
     
-    s.write('  ROS_DECLARE_ALLINONE_SERIALIZER;\n')
+    s.write('  ROS_DECLARE_ALLINONE_SERIALIZER\n')
     
     s.write('}; // struct %s_\n'%(spec.short_name))
         
diff --git a/clients/roscpp/src/libros/connection.cpp b/clients/roscpp/src/libros/connection.cpp
index e75fd07..cb92aa7 100644
--- a/clients/roscpp/src/libros/connection.cpp
+++ b/clients/roscpp/src/libros/connection.cpp
@@ -98,6 +98,7 @@ void Connection::removeDropListener(const boost::signals2::connection& c)
 
 void Connection::onReadable(const TransportPtr& transport)
 {
+  (void)transport;
   ROS_ASSERT(transport == transport_);
 
   readTransport();
@@ -254,6 +255,7 @@ void Connection::writeTransport()
 
 void Connection::onWriteable(const TransportPtr& transport)
 {
+  (void)transport;
   ROS_ASSERT(transport == transport_);
 
   writeTransport();
@@ -314,6 +316,7 @@ void Connection::write(const boost::shared_array<uint8_t>& buffer, uint32_t size
 
 void Connection::onDisconnect(const TransportPtr& transport)
 {
+  (void)transport;
   ROS_ASSERT(transport == transport_);
 
   drop(TransportDisconnect);
@@ -379,6 +382,7 @@ void Connection::sendHeaderError(const std::string& error_msg)
 
 void Connection::onHeaderLengthRead(const ConnectionPtr& conn, const boost::shared_array<uint8_t>& buffer, uint32_t size, bool success)
 {
+  (void)size;
   ROS_ASSERT(conn.get() == this);
   ROS_ASSERT(size == 4);
 
diff --git a/clients/roscpp/src/libros/init.cpp b/clients/roscpp/src/libros/init.cpp
index 920e665..8837898 100644
--- a/clients/roscpp/src/libros/init.cpp
+++ b/clients/roscpp/src/libros/init.cpp
@@ -148,6 +148,7 @@ void atexitCallback()
   if (ok() && !isShuttingDown())
   {
     ROSCPP_LOG_DEBUG("shutting down due to exit() or end of main() without cleanup of all NodeHandles");
+    g_started = false; // don't shutdown singletons, because they are already destroyed
     shutdown();
   }
 }
diff --git a/clients/roscpp/src/libros/param.cpp b/clients/roscpp/src/libros/param.cpp
index 8858a40..e7b1ffb 100644
--- a/clients/roscpp/src/libros/param.cpp
+++ b/clients/roscpp/src/libros/param.cpp
@@ -170,11 +170,10 @@ void set(const std::string& key, const std::vector<bool>& vec)
 template <class T>
   void setImpl(const std::string& key, const std::map<std::string, T>& map)
 {
-  // Note: the XmlRpcValue starts off as "invalid" and assertArray turns it
-  // into an array type with the given size
+  // Note: the XmlRpcValue starts off as "invalid" and assertStruct turns it
+  // into a struct type
   XmlRpc::XmlRpcValue xml_value;
-  const XmlRpc::XmlRpcValue::ValueStruct& xml_map = (const XmlRpc::XmlRpcValue::ValueStruct &)(xml_value);
-  (void)xml_map;
+  xml_value.begin();
 
   // Copy the contents into the XmlRpcValue
   for(typename std::map<std::string, T>::const_iterator it = map.begin(); it != map.end(); ++it) {
diff --git a/clients/roscpp/src/libros/service_client_link.cpp b/clients/roscpp/src/libros/service_client_link.cpp
index 7ea4638..830b4ed 100644
--- a/clients/roscpp/src/libros/service_client_link.cpp
+++ b/clients/roscpp/src/libros/service_client_link.cpp
@@ -162,6 +162,7 @@ bool ServiceClientLink::handleHeader(const Header& header)
 
 void ServiceClientLink::onConnectionDropped(const ConnectionPtr& conn)
 {
+  (void)conn;
   ROS_ASSERT(conn == connection_);
 
   if (ServicePublicationPtr parent = parent_.lock())
@@ -178,6 +179,7 @@ void ServiceClientLink::onHeaderWritten(const ConnectionPtr& conn)
 
 void ServiceClientLink::onRequestLength(const ConnectionPtr& conn, const boost::shared_array<uint8_t>& buffer, uint32_t size, bool success)
 {
+  (void)size;
   if (!success)
     return;
 
@@ -201,6 +203,7 @@ void ServiceClientLink::onRequestLength(const ConnectionPtr& conn, const boost::
 
 void ServiceClientLink::onRequest(const ConnectionPtr& conn, const boost::shared_array<uint8_t>& buffer, uint32_t size, bool success)
 {
+  (void)conn;
   if (!success)
     return;
 
@@ -218,6 +221,7 @@ void ServiceClientLink::onRequest(const ConnectionPtr& conn, const boost::shared
 
 void ServiceClientLink::onResponseWritten(const ConnectionPtr& conn)
 {
+  (void)conn;
   ROS_ASSERT(conn == connection_);
 
   if (persistent_)
diff --git a/clients/roscpp/src/libros/service_manager.cpp b/clients/roscpp/src/libros/service_manager.cpp
index 09f6f3d..2bdb022 100644
--- a/clients/roscpp/src/libros/service_manager.cpp
+++ b/clients/roscpp/src/libros/service_manager.cpp
@@ -52,20 +52,10 @@ using namespace std; // sigh
 namespace ros
 {
 
-ServiceManagerPtr g_service_manager;
-boost::mutex g_service_manager_mutex;
 const ServiceManagerPtr& ServiceManager::instance()
 {
-  if (!g_service_manager)
-  {
-    boost::mutex::scoped_lock lock(g_service_manager_mutex);
-    if (!g_service_manager)
-    {
-      g_service_manager = boost::make_shared<ServiceManager>();
-    }
-  }
-
-  return g_service_manager;
+  static ServiceManagerPtr service_manager = boost::make_shared<ServiceManager>();
+  return service_manager;
 }
 
 ServiceManager::ServiceManager()
diff --git a/clients/roscpp/src/libros/service_server_link.cpp b/clients/roscpp/src/libros/service_server_link.cpp
index 593d6fc..62fbbdc 100644
--- a/clients/roscpp/src/libros/service_server_link.cpp
+++ b/clients/roscpp/src/libros/service_server_link.cpp
@@ -186,6 +186,7 @@ void ServiceServerLink::onRequestWritten(const ConnectionPtr& conn)
 
 void ServiceServerLink::onResponseOkAndLength(const ConnectionPtr& conn, const boost::shared_array<uint8_t>& buffer, uint32_t size, bool success)
 {
+  (void)size;
   ROS_ASSERT(conn == connection_);
   ROS_ASSERT(size == 5);
 
@@ -227,6 +228,7 @@ void ServiceServerLink::onResponseOkAndLength(const ConnectionPtr& conn, const b
 
 void ServiceServerLink::onResponse(const ConnectionPtr& conn, const boost::shared_array<uint8_t>& buffer, uint32_t size, bool success)
 {
+  (void)conn;
   ROS_ASSERT(conn == connection_);
 
   if (!success)
diff --git a/clients/roscpp/src/libros/spinner.cpp b/clients/roscpp/src/libros/spinner.cpp
index 9981aaa..4bae89a 100644
--- a/clients/roscpp/src/libros/spinner.cpp
+++ b/clients/roscpp/src/libros/spinner.cpp
@@ -30,10 +30,111 @@
 #include "ros/callback_queue.h"
 
 #include <boost/thread/thread.hpp>
-#include <boost/thread/recursive_mutex.hpp>
+#include <boost/thread/mutex.hpp>
 
 namespace {
-  boost::recursive_mutex spinmutex;
+
+const std::string DEFAULT_ERROR_MESSAGE =
+    "\nAttempt to spin a callback queue from two spinners, one of them being single-threaded."
+    "\nThis will probably result in callbacks being executed out-of-order."
+    "\nIn future this will throw an exception!";
+
+/** class to monitor running single-threaded spinners.
+ *
+ *  Calling the callbacks of a callback queue _in order_, requires a unique SingleThreadedSpinner
+ *  spinning on the queue. Other threads accessing the callback queue will probably intercept execution order.
+
+ *  To avoid multiple SingleThreadedSpinners (started from different threads) to operate on the same callback queue,
+ *  this class stores a map of all spinned callback queues.
+ *  If the spinner is single threaded, the corresponding thread-id is stored in the map
+ *  and if other threads will try to spin the same queue, an error message is issued.
+ *
+ *  If the spinner is multi-threaded, the stored thread-id is NULL and future SingleThreadedSpinners
+ *  should not spin this queue. However, other multi-threaded spinners are allowed.
+ */
+struct SpinnerMonitor
+{
+  /* store spinner information per callback queue:
+     Only alike spinners (single-threaded or multi-threaded) are allowed on a callback queue.
+     For single-threaded spinners we store their thread id.
+     We store the number of alike spinners operating on the callback queue.
+  */
+  struct Entry
+  {
+    Entry(const boost::thread::id &tid,
+          const boost::thread::id &initial_tid) : tid(tid), initial_tid(initial_tid), num(0) {}
+
+    boost::thread::id tid; // proper thread id of single-threaded spinner
+    boost::thread::id initial_tid; // to retain old behaviour, store first spinner's thread id
+    unsigned int num; // number of (alike) spinners serving this queue
+  };
+
+  /// add a queue to the list
+  bool add(ros::CallbackQueue* queue, bool single_threaded)
+  {
+    boost::mutex::scoped_lock lock(mutex_);
+
+    boost::thread::id current_tid = boost::this_thread::get_id();
+    boost::thread::id tid; // current thread id for single-threaded spinners, zero for multi-threaded ones
+    if (single_threaded)
+      tid = current_tid;
+
+    std::map<ros::CallbackQueue*, Entry>::iterator it = spinning_queues_.find(queue);
+    bool can_spin = ( it == spinning_queues_.end() || // we will spin on any new queue
+                      it->second.tid == tid ); // otherwise spinner must be alike (all multi-threaded: 0, or single-threaded on same thread id)
+
+    if (!can_spin)
+    {
+      // Previous behavior (up to Kinetic) was to accept multiple spinners on a queue
+      // as long as they were started from the same thread. Although this is wrong behavior,
+      // we retain it here for backwards compatibility, i.e. we allow spinning of a
+      // single-threaded spinner after several multi-threaded ones, given that they
+      // were started from the same initial thread
+      if (it->second.initial_tid == tid)
+      {
+        ROS_ERROR_STREAM("SpinnerMonitor: single-threaded spinner after multi-threaded one(s)."
+                         << DEFAULT_ERROR_MESSAGE
+                         << " Only allowed for backwards compatibility.");
+        it->second.tid = tid; // "upgrade" tid to represent single-threaded spinner
+      }
+      else
+        return false;
+    }
+
+    if (it == spinning_queues_.end())
+      it = spinning_queues_.insert(it, std::make_pair(queue, Entry(tid, current_tid)));
+
+    // increment number of active spinners
+    it->second.num += 1;
+
+    return true;
+  }
+
+  /// remove a queue from the list
+  void remove(ros::CallbackQueue* queue)
+  {
+    boost::mutex::scoped_lock lock(mutex_);
+    std::map<ros::CallbackQueue*, Entry>::iterator it = spinning_queues_.find(queue);
+    ROS_ASSERT_MSG(it != spinning_queues_.end(), "Call to SpinnerMonitor::remove() without matching call to add().");
+
+    if (it->second.tid != boost::thread::id() && it->second.tid != boost::this_thread::get_id())
+    {
+      // This doesn't harm, but isn't good practice?
+      // It was enforced by the previous implementation.
+      ROS_WARN("SpinnerMonitor::remove() called from different thread than add().");
+    }
+
+    ROS_ASSERT_MSG(it->second.num > 0, "SpinnerMonitor::remove(): Invalid spinner count (0) encountered.");
+    it->second.num -= 1;
+    if (it->second.num == 0)
+      spinning_queues_.erase(it); // erase queue entry to allow future queues with same pointer
+  }
+
+  std::map<ros::CallbackQueue*, Entry> spinning_queues_;
+  boost::mutex mutex_;
+};
+
+SpinnerMonitor spinner_monitor;
 }
 
 namespace ros
@@ -42,25 +143,24 @@ namespace ros
 
 void SingleThreadedSpinner::spin(CallbackQueue* queue)
 {
-  boost::recursive_mutex::scoped_try_lock spinlock(spinmutex);
-  if(!spinlock.owns_lock()) {
-    ROS_ERROR("SingleThreadedSpinner: You've attempted to call spin "
-              "from multiple threads.  Use a MultiThreadedSpinner instead.");
-    return;
-  }
-
-  ros::WallDuration timeout(0.1f);
-
   if (!queue)
   {
     queue = getGlobalCallbackQueue();
   }
 
+  if (!spinner_monitor.add(queue, true))
+  {
+    ROS_ERROR_STREAM("SingleThreadedSpinner: " << DEFAULT_ERROR_MESSAGE);
+    return;
+  }
+
+  ros::WallDuration timeout(0.1f);
   ros::NodeHandle n;
   while (n.ok())
   {
     queue->callAvailable(timeout);
   }
+  spinner_monitor.remove(queue);
 }
 
 MultiThreadedSpinner::MultiThreadedSpinner(uint32_t thread_count)
@@ -70,13 +170,6 @@ MultiThreadedSpinner::MultiThreadedSpinner(uint32_t thread_count)
 
 void MultiThreadedSpinner::spin(CallbackQueue* queue)
 {
-  boost::recursive_mutex::scoped_try_lock spinlock(spinmutex);
-  if (!spinlock.owns_lock()) {
-    ROS_ERROR("MultiThreadeSpinner: You've attempted to call ros::spin "
-              "from multiple threads... "
-              "but this spinner is already multithreaded.");
-    return;
-  }
   AsyncSpinner s(thread_count_, queue);
   s.start();
 
@@ -97,7 +190,6 @@ private:
   void threadFunc();
 
   boost::mutex mutex_;
-  boost::recursive_mutex::scoped_try_lock member_spinlock;
   boost::thread_group threads_;
 
   uint32_t thread_count_;
@@ -136,8 +228,7 @@ AsyncSpinnerImpl::~AsyncSpinnerImpl()
 
 bool AsyncSpinnerImpl::canStart()
 {
-  boost::recursive_mutex::scoped_try_lock spinlock(spinmutex);
-  return spinlock.owns_lock();
+  return true;
 }
 
 void AsyncSpinnerImpl::start()
@@ -145,18 +236,13 @@ void AsyncSpinnerImpl::start()
   boost::mutex::scoped_lock lock(mutex_);
 
   if (continue_)
-    return;
+    return; // already spinning
 
-  boost::recursive_mutex::scoped_try_lock spinlock(spinmutex);
-  if (!spinlock.owns_lock()) {
-    ROS_WARN("AsyncSpinnerImpl: Attempt to start() an AsyncSpinner failed "
-             "because another AsyncSpinner is already running. Note that the "
-             "other AsyncSpinner might not be using the same callback queue "
-             "as this AsyncSpinner, in which case no callbacks in your "
-             "callback queue will be serviced.");
+  if (!spinner_monitor.add(callback_queue_, false))
+  {
+    ROS_ERROR_STREAM("AsyncSpinnerImpl: " << DEFAULT_ERROR_MESSAGE);
     return;
   }
-  spinlock.swap(member_spinlock);
 
   continue_ = true;
 
@@ -172,14 +258,10 @@ void AsyncSpinnerImpl::stop()
   if (!continue_)
     return;
 
-  ROS_ASSERT_MSG(member_spinlock.owns_lock(), 
-                 "Async spinner's member lock doesn't own the global spinlock, hrm.");
-  ROS_ASSERT_MSG(member_spinlock.mutex() == &spinmutex, 
-                 "Async spinner's member lock owns a lock on the wrong mutex?!?!?");
-  member_spinlock.unlock();
-
   continue_ = false;
   threads_.join_all();
+
+  spinner_monitor.remove(callback_queue_);
 }
 
 void AsyncSpinnerImpl::threadFunc()
diff --git a/clients/roscpp/src/libros/subscription_queue.cpp b/clients/roscpp/src/libros/subscription_queue.cpp
index e436bb8..67b3255 100644
--- a/clients/roscpp/src/libros/subscription_queue.cpp
+++ b/clients/roscpp/src/libros/subscription_queue.cpp
@@ -64,7 +64,7 @@ void SubscriptionQueue::push(const SubscriptionCallbackHelperPtr& helper, const
 
     if (!full_)
     {
-      ROS_DEBUG("Incoming queue full for topic \"%s\".  Discarding oldest message (current queue size [%d])", topic_.c_str(), (int)queue_.size());
+      ROS_DEBUG("Incoming queue was full for topic \"%s\". Discarded oldest message (current queue size [%d])", topic_.c_str(), (int)queue_.size());
     }
 
     full_ = true;
diff --git a/clients/roscpp/src/libros/this_node.cpp b/clients/roscpp/src/libros/this_node.cpp
index 3149476..7f15d73 100644
--- a/clients/roscpp/src/libros/this_node.cpp
+++ b/clients/roscpp/src/libros/this_node.cpp
@@ -49,17 +49,43 @@ void init(const M_string& remappings);
 namespace this_node
 {
 
-std::string g_name = "empty";
-std::string g_namespace;
+// collect all static variables into a singleton to ensure proper destruction order
+class ThisNode
+{
+  std::string name_;
+  std::string namespace_;
+
+  ThisNode() : name_("empty") {}
+
+public:
+  static ThisNode& instance()
+  {
+    static ThisNode singleton;
+    return singleton;
+  }
+
+  const std::string& getName() const
+  {
+    return name_;
+  }
+
+  const std::string& getNamespace() const
+  {
+    return namespace_;
+  }
+
+  void init(const std::string& name, const M_string& remappings, uint32_t options);
+};
+
 
 const std::string& getName()
 {
-  return g_name;
+  return ThisNode::instance().getName();
 }
 
 const std::string& getNamespace()
 {
-  return g_namespace;
+  return ThisNode::instance().getNamespace();
 }
 
 void getAdvertisedTopics(V_string& topics)
@@ -74,6 +100,11 @@ void getSubscribedTopics(V_string& topics)
 
 void init(const std::string& name, const M_string& remappings, uint32_t options)
 {
+  ThisNode::instance().init(name, remappings, options);
+}
+
+void ThisNode::init(const std::string& name, const M_string& remappings, uint32_t options)
+{
   char *ns_env = NULL;
 #ifdef _MSC_VER
   _dupenv_s(&ns_env, NULL, "ROS_NAMESPACE");
@@ -83,44 +114,48 @@ void init(const std::string& name, const M_string& remappings, uint32_t options)
 
   if (ns_env)
   {
-    g_namespace = ns_env;
+    namespace_ = ns_env;
 #ifdef _MSC_VER
     free(ns_env);
 #endif
   }
 
-  g_name = name;
+  if (name.empty()) {
+    throw InvalidNameException("The node name must not be empty");
+  }
+
+  name_ = name;
 
   bool disable_anon = false;
   M_string::const_iterator it = remappings.find("__name");
   if (it != remappings.end())
   {
-    g_name = it->second;
+    name_ = it->second;
     disable_anon = true;
   }
 
   it = remappings.find("__ns");
   if (it != remappings.end())
   {
-    g_namespace = it->second;
+    namespace_ = it->second;
   }
 
-  if (g_namespace.empty())
+  if (namespace_.empty())
   {
-    g_namespace = "/";
+    namespace_ = "/";
   }
 
-  g_namespace = (g_namespace == "/")
+  namespace_ = (namespace_ == "/")
     ? std::string("/") 
-    : ("/" + g_namespace)
+    : ("/" + namespace_)
     ;
 
 
   std::string error;
-  if (!names::validate(g_namespace, error))
+  if (!names::validate(namespace_, error))
   {
     std::stringstream ss;
-    ss << "Namespace [" << g_namespace << "] is invalid: " << error;
+    ss << "Namespace [" << namespace_ << "] is invalid: " << error;
     throw InvalidNameException(ss.str());
   }
 
@@ -128,25 +163,25 @@ void init(const std::string& name, const M_string& remappings, uint32_t options)
   // It must be done before we resolve g_name, because otherwise the name will not get remapped.
   names::init(remappings);
 
-  if (g_name.find("/") != std::string::npos)
+  if (name_.find("/") != std::string::npos)
   {
-    throw InvalidNodeNameException(g_name, "node names cannot contain /");
+    throw InvalidNodeNameException(name_, "node names cannot contain /");
   }
-  if (g_name.find("~") != std::string::npos)
+  if (name_.find("~") != std::string::npos)
   {
-    throw InvalidNodeNameException(g_name, "node names cannot contain ~");
+    throw InvalidNodeNameException(name_, "node names cannot contain ~");
   }
 
-  g_name = names::resolve(g_namespace, g_name);
+  name_ = names::resolve(namespace_, name_);
 
   if (options & init_options::AnonymousName && !disable_anon)
   {
     char buf[200];
     snprintf(buf, sizeof(buf), "_%llu", (unsigned long long)WallTime::now().toNSec());
-    g_name += buf;
+    name_ += buf;
   }
 
-  ros::console::setFixedFilterToken("node", g_name);
+  ros::console::setFixedFilterToken("node", name_);
 }
 
 } // namespace this_node
diff --git a/clients/roscpp/src/libros/topic_manager.cpp b/clients/roscpp/src/libros/topic_manager.cpp
index 2b0a4e6..3d77e7c 100644
--- a/clients/roscpp/src/libros/topic_manager.cpp
+++ b/clients/roscpp/src/libros/topic_manager.cpp
@@ -102,6 +102,9 @@ void TopicManager::shutdown()
     shutting_down_ = true;
   }
 
+  // actually one should call poll_manager_->removePollThreadListener(), but the connection is not stored above
+  poll_manager_->shutdown();
+
   xmlrpc_manager_->unbind("publisherUpdate");
   xmlrpc_manager_->unbind("requestTopic");
   xmlrpc_manager_->unbind("getBusStats");
diff --git a/clients/roscpp/src/libros/transport_publisher_link.cpp b/clients/roscpp/src/libros/transport_publisher_link.cpp
index d1929f6..6b28f68 100644
--- a/clients/roscpp/src/libros/transport_publisher_link.cpp
+++ b/clients/roscpp/src/libros/transport_publisher_link.cpp
@@ -125,6 +125,7 @@ void TransportPublisherLink::onHeaderWritten(const ConnectionPtr& conn)
 
 bool TransportPublisherLink::onHeaderReceived(const ConnectionPtr& conn, const Header& header)
 {
+  (void)conn;
   ROS_ASSERT(conn == connection_);
 
   if (!setHeader(header))
@@ -146,6 +147,8 @@ bool TransportPublisherLink::onHeaderReceived(const ConnectionPtr& conn, const H
 
 void TransportPublisherLink::onMessageLength(const ConnectionPtr& conn, const boost::shared_array<uint8_t>& buffer, uint32_t size, bool success)
 {
+  (void)conn;
+  (void)size;
   if (retry_timer_handle_ != -1)
   {
     getInternalTimerManager()->remove(retry_timer_handle_);
@@ -247,6 +250,7 @@ CallbackQueuePtr getInternalCallbackQueue();
 
 void TransportPublisherLink::onConnectionDropped(const ConnectionPtr& conn, Connection::DropReason reason)
 {
+  (void)conn;
   if (dropping_)
   {
     return;
diff --git a/clients/roscpp/src/libros/transport_subscriber_link.cpp b/clients/roscpp/src/libros/transport_subscriber_link.cpp
index ace5aa4..2257a9a 100644
--- a/clients/roscpp/src/libros/transport_subscriber_link.cpp
+++ b/clients/roscpp/src/libros/transport_subscriber_link.cpp
@@ -121,6 +121,7 @@ bool TransportSubscriberLink::handleHeader(const Header& header)
 
 void TransportSubscriberLink::onConnectionDropped(const ConnectionPtr& conn)
 {
+  (void)conn;
   ROS_ASSERT(conn == connection_);
 
   PublicationPtr parent = parent_.lock();
diff --git a/clients/rospy/CHANGELOG.rst b/clients/rospy/CHANGELOG.rst
index e230100..c705234 100644
--- a/clients/rospy/CHANGELOG.rst
+++ b/clients/rospy/CHANGELOG.rst
@@ -2,6 +2,12 @@
 Changelog for package rospy
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.12.3 (2016-09-17)
+-------------------
+* raise error on rospy.init_node with None or empty node name string (`#895 <https://github.com/ros/ros_comm/pull/895>`_)
+* fix wrong type in docstring for rospy.Timer (`#878 <https://github.com/ros/ros_comm/pull/878>`_)
+* fix order of init and publisher in example (`#873 <https://github.com/ros/ros_comm/pull/873>`_)
+
 1.12.2 (2016-06-03)
 -------------------
 * add logXXX_throttle functions (`#812 <https://github.com/ros/ros_comm/pull/812>`_)
diff --git a/clients/rospy/package.xml b/clients/rospy/package.xml
index 68abcfc..544112f 100644
--- a/clients/rospy/package.xml
+++ b/clients/rospy/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>rospy</name>
-  <version>1.12.2</version>
+  <version>1.12.3</version>
   <description>
     rospy is a pure Python client library for ROS. The rospy client
     API enables Python programmers to quickly interface with ROS <a
diff --git a/clients/rospy/src/rospy/client.py b/clients/rospy/src/rospy/client.py
index 596903f..f167ee4 100644
--- a/clients/rospy/src/rospy/client.py
+++ b/clients/rospy/src/rospy/client.py
@@ -257,7 +257,10 @@ def init_node(name, argv=None, anonymous=False, log_level=None, disable_rostime=
         # reload the mapping table. Any previously created rospy data
         # structure does *not* reinitialize based on the new mappings.
         rospy.names.reload_mappings(argv)
-        
+
+    if not name:
+        raise ValueError("name must not be empty")
+
     # this test can be eliminated once we change from warning to error in the next check
     if rosgraph.names.SEP in name:
         raise ValueError("namespaces are not allowed in node names")
diff --git a/clients/rospy/src/rospy/timer.py b/clients/rospy/src/rospy/timer.py
index 4ddf491..b587426 100644
--- a/clients/rospy/src/rospy/timer.py
+++ b/clients/rospy/src/rospy/timer.py
@@ -185,7 +185,7 @@ class Timer(threading.Thread):
         """
         Constructor.
         @param period: desired period between callbacks
-        @type  period: rospy.Time
+        @type  period: rospy.Duration
         @param callback: callback to be called
         @type  callback: function taking rospy.TimerEvent
         @param oneshot: if True, fire only once, otherwise fire continuously until shutdown is called [default: False]
diff --git a/clients/rospy/test_nodes/talker.py b/clients/rospy/test_nodes/talker.py
index ed67fed..271d9f0 100755
--- a/clients/rospy/test_nodes/talker.py
+++ b/clients/rospy/test_nodes/talker.py
@@ -38,8 +38,8 @@ import rospy
 from std_msgs.msg import String
 
 def talker():
-    pub = rospy.Publisher('chatter', String, queue_size=10)
     rospy.init_node('talker', anonymous=True)
+    pub = rospy.Publisher('chatter', String, queue_size=10)
     r = rospy.Rate(10) # 10hz
     while not rospy.is_shutdown():
         str = "hello world %s"%rospy.get_time()
diff --git a/ros_comm/CHANGELOG.rst b/ros_comm/CHANGELOG.rst
index 0b64f35..dc76189 100644
--- a/ros_comm/CHANGELOG.rst
+++ b/ros_comm/CHANGELOG.rst
@@ -2,6 +2,9 @@
 Changelog for package ros_comm
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.12.3 (2016-09-17)
+-------------------
+
 1.12.2 (2016-06-03)
 -------------------
 
diff --git a/ros_comm/package.xml b/ros_comm/package.xml
index b5dc7f3..475cda9 100644
--- a/ros_comm/package.xml
+++ b/ros_comm/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>ros_comm</name>
-  <version>1.12.2</version>
+  <version>1.12.3</version>
   <description>
     ROS communications-related packages, including core client libraries (roscpp, rospy) and graph introspection tools (rostopic, rosnode, rosservice, rosparam).
   </description>
diff --git a/test/test_rosbag/CMakeLists.txt b/test/test_rosbag/CMakeLists.txt
index 41f60b4..534403f 100644
--- a/test/test_rosbag/CMakeLists.txt
+++ b/test/test_rosbag/CMakeLists.txt
@@ -54,7 +54,7 @@ if(CATKIN_ENABLE_TESTING)
   include_directories(${GTEST_INCLUDE_DIRS})
   add_executable(double_pub EXCLUDE_FROM_ALL test/double_pub.cpp)
   target_link_libraries(double_pub ${GTEST_LIBRARIES} ${catkin_LIBRARIES})
-  add_dependencies(double_pub rosgraph_msgs_genpy)
+  add_dependencies(double_pub ${rosgraph_msgs_EXPORTED_TARGETS})
   if(TARGET tests)
     add_dependencies(tests double_pub)
   endif()
diff --git a/test/test_rosbag/package.xml b/test/test_rosbag/package.xml
index c8affa3..ed60757 100644
--- a/test/test_rosbag/package.xml
+++ b/test/test_rosbag/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>test_rosbag</name>
-  <version>1.12.2</version>
+  <version>1.12.3</version>
   <description>
     A package containing the unit tests for rosbag.
   </description>
diff --git a/test/test_rosbag_storage/package.xml b/test/test_rosbag_storage/package.xml
index dac2976..ac65799 100644
--- a/test/test_rosbag_storage/package.xml
+++ b/test/test_rosbag_storage/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>test_rosbag_storage</name>
-  <version>1.12.2</version>
+  <version>1.12.3</version>
   <description>
     A package containing the unit tests for rosbag_storage.
   </description>
diff --git a/test/test_roscpp/package.xml b/test/test_roscpp/package.xml
index 58c01b7..edd99b5 100644
--- a/test/test_roscpp/package.xml
+++ b/test/test_roscpp/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>test_roscpp</name>
-  <version>1.12.2</version>
+  <version>1.12.3</version>
   <description>
     Tests for roscpp which depend on rostest.
   </description>
diff --git a/test/test_roscpp/test/CMakeLists.txt b/test/test_roscpp/test/CMakeLists.txt
index e510c69..7328a59 100644
--- a/test/test_roscpp/test/CMakeLists.txt
+++ b/test/test_roscpp/test/CMakeLists.txt
@@ -3,21 +3,6 @@ if(TARGET ${PROJECT_NAME}-test_version)
   target_link_libraries(${PROJECT_NAME}-test_version)
 endif()
 
-# WARNING test_spinners is not actually run.  This is because this
-# infrastructure won't let me pass arguments from here through to
-# these test units.  otherwise one would have to build ten executables.
-# also the output of test_spinners has to be visually inspected
-# because there is no automatic way to ensure that an error condition
-# provokes a particular message.
-if(GTEST_FOUND)
-  include_directories(${GTEST_INCLUDE_DIRS})
-  add_executable(${PROJECT_NAME}-test_spinners EXCLUDE_FROM_ALL test_spinners.cpp)
-  add_dependencies(tests ${PROJECT_NAME}-test_spinners) 
-endif()
-if(TARGET ${PROJECT_NAME}-test_spinners)
-  target_link_libraries(${PROJECT_NAME}-test_spinners ${catkin_LIBRARIES} ${GTEST_LIBRARIES})
-endif()
-
 catkin_add_gtest(${PROJECT_NAME}-test_header test_header.cpp)
 if(TARGET ${PROJECT_NAME}-test_header)
   target_link_libraries(${PROJECT_NAME}-test_header ${catkin_LIBRARIES})
@@ -161,3 +146,6 @@ add_rostest(launch/ns_node_remapping.xml)
 add_rostest(launch/search_param.xml)
 
 add_rostest(launch/stamped_topic_statistics_with_empty_timestamp.xml)
+
+# Test spinners
+add_rostest(launch/spinners.xml)
diff --git a/test/test_roscpp/test/launch/spinners.xml b/test/test_roscpp/test/launch/spinners.xml
new file mode 100644
index 0000000..15650a8
--- /dev/null
+++ b/test/test_roscpp/test/launch/spinners.xml
@@ -0,0 +1,4 @@
+<launch>
+  <test pkg="test_roscpp" type="test_roscpp-spinners" test-name="Spinners_spin" args="--gtest_filter=Spinners.spin"/>
+  <test pkg="test_roscpp" type="test_roscpp-spinners" test-name="Spinners_multi" args="--gtest_filter=Spinners.multi"/>
+</launch>
diff --git a/test/test_roscpp/test/src/CMakeLists.txt b/test/test_roscpp/test/src/CMakeLists.txt
index 54f086d..332f49b 100644
--- a/test/test_roscpp/test/src/CMakeLists.txt
+++ b/test/test_roscpp/test/src/CMakeLists.txt
@@ -125,6 +125,10 @@ target_link_libraries(${PROJECT_NAME}-namespaces ${GTEST_LIBRARIES} ${catkin_LIB
 add_executable(${PROJECT_NAME}-params EXCLUDE_FROM_ALL params.cpp)
 target_link_libraries(${PROJECT_NAME}-params ${GTEST_LIBRARIES} ${catkin_LIBRARIES})
 
+# Test spinners
+add_executable(${PROJECT_NAME}-spinners EXCLUDE_FROM_ALL spinners.cpp)
+target_link_libraries(${PROJECT_NAME}-spinners ${GTEST_LIBRARIES} ${catkin_LIBRARIES})
+
 # Test getting information from the master
 add_executable(${PROJECT_NAME}-get_master_information EXCLUDE_FROM_ALL get_master_information.cpp)
 target_link_libraries(${PROJECT_NAME}-get_master_information ${GTEST_LIBRARIES} ${catkin_LIBRARIES})
@@ -251,6 +255,7 @@ if(TARGET tests)
     ${PROJECT_NAME}-name_remapping_with_ns
     ${PROJECT_NAME}-namespaces
     ${PROJECT_NAME}-params
+    ${PROJECT_NAME}-spinners
     ${PROJECT_NAME}-get_master_information
     ${PROJECT_NAME}-multiple_subscriptions
     ${PROJECT_NAME}-check_master
@@ -316,6 +321,7 @@ add_dependencies(${PROJECT_NAME}-name_remapping ${${PROJECT_NAME}_EXPORTED_TARGE
 add_dependencies(${PROJECT_NAME}-name_remapping_with_ns ${${PROJECT_NAME}_EXPORTED_TARGETS})
 add_dependencies(${PROJECT_NAME}-namespaces ${${PROJECT_NAME}_EXPORTED_TARGETS})
 add_dependencies(${PROJECT_NAME}-params ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-spinners ${${PROJECT_NAME}_EXPORTED_TARGETS})
 add_dependencies(${PROJECT_NAME}-get_master_information ${${PROJECT_NAME}_EXPORTED_TARGETS})
 add_dependencies(${PROJECT_NAME}-multiple_subscriptions ${${PROJECT_NAME}_EXPORTED_TARGETS})
 add_dependencies(${PROJECT_NAME}-check_master ${${PROJECT_NAME}_EXPORTED_TARGETS})
diff --git a/test/test_roscpp/test/src/latching_publisher.cpp b/test/test_roscpp/test/src/latching_publisher.cpp
index f24b1f3..cd4beeb 100644
--- a/test/test_roscpp/test/src/latching_publisher.cpp
+++ b/test/test_roscpp/test/src/latching_publisher.cpp
@@ -1,5 +1,5 @@
 /*
- * Copyright (c) 2NULLNULL8, Willow Garage, Inc.
+ * Copyright (c) 2008, Willow Garage, Inc.
  * All rights reserved.
  *
  * Redistribution and use in source and binary forms, with or without
diff --git a/test/test_roscpp/test/test_spinners.cpp b/test/test_roscpp/test/src/spinners.cpp
similarity index 63%
rename from test/test_roscpp/test/test_spinners.cpp
rename to test/test_roscpp/test/src/spinners.cpp
index 8645399..b94ae0d 100644
--- a/test/test_roscpp/test/test_spinners.cpp
+++ b/test/test_roscpp/test/src/spinners.cpp
@@ -67,76 +67,96 @@ void fire_shutdown(const ros::WallTimerEvent&) {
 TEST(Spinners, spin)
 {
   DOIT();
-  ros::spin();
+  ros::spin(); // will block until ROS shutdown
 }
 
 TEST(Spinners, spinfail)
 {
   DOIT();
   boost::thread th(boost::bind(&ros::spin));
-  ros::spin();
-}
+  ros::WallDuration(0.1).sleep(); // wait for thread to be started
 
-TEST(Spinners, single)
-{
-  DOIT();
-  SingleThreadedSpinner s;
-  ros::spin(s);
+  EXPECT_THROW(ros::spin(), std::runtime_error);
+
+  SingleThreadedSpinner ss;
+  EXPECT_THROW(ros::spin(ss), std::runtime_error);
+  EXPECT_THROW(ss.spin(), std::runtime_error);
+
+  MultiThreadedSpinner ms;
+  EXPECT_THROW(ros::spin(ms), std::runtime_error);
+  EXPECT_THROW(ms.spin(), std::runtime_error);
+
+  AsyncSpinner as(2);
+  EXPECT_THROW(as.start(), std::runtime_error);
+
+  ros::waitForShutdown();
 }
 
 TEST(Spinners, singlefail)
 {
   DOIT();
-  boost::thread th(boost::bind(&ros::spin));
-  SingleThreadedSpinner s;
-  ros::spin(s);
-}
+  SingleThreadedSpinner ss;
+  boost::thread th(boost::bind(&ros::spin, ss));
+  ros::WallDuration(0.1).sleep(); // wait for thread to be started
 
-TEST(Spinners, singlefail2)
-{
-  DOIT();
-  SingleThreadedSpinner s;
-  boost::thread th(boost::bind(&ros::spin, s));
-  ros::spin(s);
+  EXPECT_THROW(ros::spin(), std::runtime_error);
+
+  SingleThreadedSpinner ss2;
+  EXPECT_THROW(ros::spin(ss2), std::runtime_error);
+  EXPECT_THROW(ss2.spin(), std::runtime_error);
+
+  MultiThreadedSpinner ms;
+  EXPECT_THROW(ros::spin(ms), std::runtime_error);
+  EXPECT_THROW(ms.spin(), std::runtime_error);
+
+  AsyncSpinner as(2);
+  EXPECT_THROW(as.start(), std::runtime_error);
+
+  ros::waitForShutdown();
 }
 
 TEST(Spinners, multi)
 {
   DOIT();
-  MultiThreadedSpinner s;
-  ros::spin(s);
+  MultiThreadedSpinner ms;
+  ros::spin(ms); // will block until ROS shutdown
 }
 
 TEST(Spinners, multifail)
 {
   DOIT();
-  boost::thread th(boost::bind(&ros::spin));
-  MultiThreadedSpinner s;
-  ros::spin(s);
-}
+  MultiThreadedSpinner ms;
+  boost::thread th(boost::bind(&ros::spin, ms));
+  ros::WallDuration(0.1).sleep(); // wait for thread to be started
 
-TEST(Spinners, multifail2)
-{
-  DOIT();
-  MultiThreadedSpinner s;
-  boost::thread th(boost::bind(&ros::spin, s));
-  ros::spin(s);
+  SingleThreadedSpinner ss2;
+  EXPECT_THROW(ros::spin(ss2), std::runtime_error);
+  EXPECT_THROW(ss2.spin(), std::runtime_error);
+
+  // running another multi-threaded spinner is allowed
+  MultiThreadedSpinner ms2;
+  ros::spin(ms2); // will block until ROS shutdown
 }
 
 TEST(Spinners, async)
 {
   DOIT();
-  AsyncSpinner s(2);
-  s.start();
-  ros::waitForShutdown();
-}
+  AsyncSpinner as1(2);
+  as1.start();
+
+  // running another AsyncSpinner is allowed
+  AsyncSpinner as2(2);
+  as2.start();
+  as2.stop();
+
+  SingleThreadedSpinner ss;
+  EXPECT_THROW(ros::spin(ss), std::runtime_error);
+  EXPECT_THROW(ss.spin(), std::runtime_error);
+
+  // running a multi-threaded spinner is allowed
+  MultiThreadedSpinner ms;
+  ros::spin(ms); // will block until ROS shutdown
 
-TEST(Spinners, asyncfail)
-{
-  DOIT();
-  boost::thread th(boost::bind(&ros::spin));
-  AsyncSpinner s(2);
-  s.start();
   ros::waitForShutdown();
 }
 
@@ -149,5 +169,3 @@ main(int argc, char** argv)
   argv_ = argv;
   return RUN_ALL_TESTS();
 }
-
-
diff --git a/test/test_roscpp/test/src/subscribe_star.cpp b/test/test_roscpp/test/src/subscribe_star.cpp
index 7e6f70e..0a0e8aa 100644
--- a/test/test_roscpp/test/src/subscribe_star.cpp
+++ b/test/test_roscpp/test/src/subscribe_star.cpp
@@ -83,7 +83,7 @@ struct Serializer<AnyMessage>
   {
   }
 
-  ROS_DECLARE_ALLINONE_SERIALIZER;
+  ROS_DECLARE_ALLINONE_SERIALIZER
 };
 }
 }
diff --git a/test/test_roscpp/test/src/timer_callbacks.cpp b/test/test_roscpp/test/src/timer_callbacks.cpp
index b016ee5..9f2bc7e 100644
--- a/test/test_roscpp/test/src/timer_callbacks.cpp
+++ b/test/test_roscpp/test/src/timer_callbacks.cpp
@@ -1,5 +1,5 @@
 /*
- * Copyright (c) 2NULLNULL8, Willow Garage, Inc.
+ * Copyright (c) 2008, Willow Garage, Inc.
  * All rights reserved.
  *
  * Redistribution and use in source and binary forms, with or without
diff --git a/test/test_roscpp/test/src/wait_for_message.cpp b/test/test_roscpp/test/src/wait_for_message.cpp
index 672cdae..d18b025 100644
--- a/test/test_roscpp/test/src/wait_for_message.cpp
+++ b/test/test_roscpp/test/src/wait_for_message.cpp
@@ -1,5 +1,5 @@
 /*
- * Copyright (c) 2NULLNULL8, Willow Garage, Inc.
+ * Copyright (c) 2008, Willow Garage, Inc.
  * All rights reserved.
  *
  * Redistribution and use in source and binary forms, with or without
diff --git a/test/test_roscpp/test/test_names.cpp b/test/test_roscpp/test/test_names.cpp
index 0916ee5..a13de2e 100644
--- a/test/test_roscpp/test/test_names.cpp
+++ b/test/test_roscpp/test/test_names.cpp
@@ -34,6 +34,7 @@
  */
 
 #include <gtest/gtest.h>
+#include "ros/init.h"
 #include "ros/names.h"
 
 using namespace ros;
@@ -77,6 +78,13 @@ TEST(Names, parentNamespace)
   EXPECT_STREQ(std::string("/z/asdf").c_str(), names::parentNamespace("/z/asdf/b").c_str());
 }
 
+TEST(Names, init_empty_node_name)
+{
+  int argc = 0;
+  char** argv = NULL;
+  EXPECT_THROW(ros::init(argc, argv, ""), ros::InvalidNameException);
+}
+
 int
 main(int argc, char** argv)
 {
diff --git a/test/test_roscpp/test_serialization/src/serialization.cpp b/test/test_roscpp/test_serialization/src/serialization.cpp
index aec015a..fbf8f04 100644
--- a/test/test_roscpp/test_serialization/src/serialization.cpp
+++ b/test/test_roscpp/test_serialization/src/serialization.cpp
@@ -374,7 +374,7 @@ struct Serializer<AllInOneSerializer>
     stream.next(t.a);
   }
 
-  ROS_DECLARE_ALLINONE_SERIALIZER;
+  ROS_DECLARE_ALLINONE_SERIALIZER
 };
 } // namespace serialization
 } // namespace ros
diff --git a/test/test_rosgraph/package.xml b/test/test_rosgraph/package.xml
index a30effb..f92f662 100644
--- a/test/test_rosgraph/package.xml
+++ b/test/test_rosgraph/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>test_rosgraph</name>
-  <version>1.12.2</version>
+  <version>1.12.3</version>
   <description>
     Tests for rosgraph which depend on rostest.
   </description>
diff --git a/test/test_roslaunch/package.xml b/test/test_roslaunch/package.xml
index ec87b05..fbdec1c 100644
--- a/test/test_roslaunch/package.xml
+++ b/test/test_roslaunch/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>test_roslaunch</name>
-  <version>1.12.2</version>
+  <version>1.12.3</version>
   <description>
     Tests for roslaunch which depend on rostest.
   </description>
diff --git a/test/test_roslib_comm/package.xml b/test/test_roslib_comm/package.xml
index ad0839c..ed261a2 100644
--- a/test/test_roslib_comm/package.xml
+++ b/test/test_roslib_comm/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>test_roslib_comm</name>
-  <version>1.12.2</version>
+  <version>1.12.3</version>
   <description>
     Unit tests verifying that roslib is operating as expected.
   </description>
diff --git a/test/test_rosmaster/package.xml b/test/test_rosmaster/package.xml
index 90d643d..2e9d280 100644
--- a/test/test_rosmaster/package.xml
+++ b/test/test_rosmaster/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>test_rosmaster</name>
-  <version>1.12.2</version>
+  <version>1.12.3</version>
   <description>
     Tests for rosmaster which depend on rostest.
   </description>
diff --git a/test/test_rosparam/package.xml b/test/test_rosparam/package.xml
index 57571e2..133c1f0 100644
--- a/test/test_rosparam/package.xml
+++ b/test/test_rosparam/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>test_rosparam</name>
-  <version>1.12.2</version>
+  <version>1.12.3</version>
   <description>
     A package containing the unit tests for rosparam.
   </description>
diff --git a/test/test_rospy/package.xml b/test/test_rospy/package.xml
index d4f9241..920b8cc 100644
--- a/test/test_rospy/package.xml
+++ b/test/test_rospy/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>test_rospy</name>
-  <version>1.12.2</version>
+  <version>1.12.3</version>
   <description>
     rospy unit and integration test framework.
   </description>
diff --git a/test/test_rospy/test/unit/test_rospy_client.py b/test/test_rospy/test/unit/test_rospy_client.py
index 4dd9e4f..6c48e5f 100644
--- a/test/test_rospy/test/unit/test_rospy_client.py
+++ b/test/test_rospy/test/unit/test_rospy_client.py
@@ -54,6 +54,20 @@ class TestRospyClient(unittest.TestCase):
             failed = False
         self.failIf(failed, "init_node allowed '/' in name")
 
+        failed = True
+        try:
+            rospy.init_node(name=None)
+        except ValueError:
+            failed = False
+        self.failIf(failed, "init_node allowed None as name")
+
+        failed = True
+        try:
+            rospy.init_node("")
+        except ValueError:
+            failed = False
+        self.failIf(failed, "init_node allowed empty string as name")
+
     def test_spin(self):
         failed = True
         try:
diff --git a/test/test_rosservice/package.xml b/test/test_rosservice/package.xml
index 0c15169..118b076 100644
--- a/test/test_rosservice/package.xml
+++ b/test/test_rosservice/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>test_rosservice</name>
-  <version>1.12.2</version>
+  <version>1.12.3</version>
   <description>
     Tests for the rosservice tool.
   </description>
diff --git a/test/test_rostopic/package.xml b/test/test_rostopic/package.xml
index 1efdd02..6fba765 100644
--- a/test/test_rostopic/package.xml
+++ b/test/test_rostopic/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>test_rostopic</name>
-  <version>1.12.2</version>
+  <version>1.12.3</version>
   <description>
     Tests for rostopic.
   </description>
diff --git a/tools/rosbag/CHANGELOG.rst b/tools/rosbag/CHANGELOG.rst
index 6f05541..b3ea3e7 100644
--- a/tools/rosbag/CHANGELOG.rst
+++ b/tools/rosbag/CHANGELOG.rst
@@ -2,6 +2,13 @@
 Changelog for package rosbag
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.12.3 (2016-09-17)
+-------------------
+* set default values for min_space and min_space_str (`#883 <https://github.com/ros/ros_comm/issues/883>`_)
+* record a maximum number of splits and then begin deleting old files (`#866 <https://github.com/ros/ros_comm/issues/866>`_)
+* allow 64-bit sizes to be passed to robag max_size (`#865 <https://github.com/ros/ros_comm/issues/865>`_)
+* update rosbag filter progress meter to use raw uncompressed input size (`#857 <https://github.com/ros/ros_comm/issues/857>`_)
+
 1.12.2 (2016-06-03)
 -------------------
 
diff --git a/tools/rosbag/include/rosbag/recorder.h b/tools/rosbag/include/rosbag/recorder.h
index c127cae..508e709 100644
--- a/tools/rosbag/include/rosbag/recorder.h
+++ b/tools/rosbag/include/rosbag/recorder.h
@@ -45,6 +45,7 @@
 #include <queue>
 #include <string>
 #include <vector>
+#include <list>
 
 #include <boost/thread/condition.hpp>
 #include <boost/thread/mutex.hpp>
@@ -103,7 +104,8 @@ struct ROSBAG_DECL RecorderOptions
     uint32_t        chunk_size;
     uint32_t        limit;
     bool            split;
-    uint32_t        max_size;
+    uint64_t        max_size;
+    uint32_t        max_splits;
     ros::Duration   max_duration;
     std::string     node;
     unsigned long long min_space;
@@ -140,6 +142,7 @@ private:
     //    void doQueue(topic_tools::ShapeShifter::ConstPtr msg, std::string const& topic, boost::shared_ptr<ros::Subscriber> subscriber, boost::shared_ptr<int> count);
     void doQueue(const ros::MessageEvent<topic_tools::ShapeShifter const>& msg_event, std::string const& topic, boost::shared_ptr<ros::Subscriber> subscriber, boost::shared_ptr<int> count);
     void doRecord();
+    void checkNumSplits();
     bool checkSize();
     bool checkDuration(const ros::Time&);
     void doRecordSnapshotter();
@@ -157,6 +160,7 @@ private:
 
     std::string                   target_filename_;
     std::string                   write_filename_;
+    std::list<std::string>        current_files_;
 
     std::set<std::string>         currently_recording_;  //!< set of currenly recording topics
     int                           num_subscribers_;      //!< used for book-keeping of our number of subscribers
diff --git a/tools/rosbag/package.xml b/tools/rosbag/package.xml
index 5a56d33..8fe241a 100644
--- a/tools/rosbag/package.xml
+++ b/tools/rosbag/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>rosbag</name>
-  <version>1.12.2</version>
+  <version>1.12.3</version>
   <description>
     This is a set of tools for recording from and playing back to ROS
     topics.  It is intended to be high performance and avoids
diff --git a/tools/rosbag/src/record.cpp b/tools/rosbag/src/record.cpp
index b23783d..dda378f 100644
--- a/tools/rosbag/src/record.cpp
+++ b/tools/rosbag/src/record.cpp
@@ -62,8 +62,9 @@ rosbag::RecorderOptions parseOptions(int argc, char** argv) {
       ("bz2,j", "use BZ2 compression")
       ("lz4", "use LZ4 compression")
       ("split", po::value<int>()->implicit_value(0), "Split the bag file and continue recording when maximum size or maximum duration reached.")
+      ("max-splits", po::value<int>()->default_value(0), "Keep a maximum of N bag files, when reaching the maximum erase the oldest one to keep a constant number of files.")
       ("topic", po::value< std::vector<std::string> >(), "topic to record")
-      ("size", po::value<int>(), "The maximum size of the bag to record in MB.")
+      ("size", po::value<uint64_t>(), "The maximum size of the bag to record in MB.")
       ("duration", po::value<std::string>(), "Record a bag of maximum duration in seconds, unless 'm', or 'h' is appended.")
       ("node", po::value<std::string>(), "Record all topics subscribed to by a specific node.");
 
@@ -123,6 +124,17 @@ rosbag::RecorderOptions parseOptions(int argc, char** argv) {
         opts.max_size = 1048576 * S;
       }
     }
+    if(vm.count("max-splits"))
+    {
+        if(!opts.split)
+        {
+            ROS_WARN("--max-splits is ignored without --split");
+        }
+        else
+        {
+            opts.max_splits = vm["max-splits"].as<int>();
+        }
+    }
     if (vm.count("buffsize"))
     {
       int m = vm["buffsize"].as<int>();
@@ -217,7 +229,7 @@ rosbag::RecorderOptions parseOptions(int argc, char** argv) {
     }
     if (vm.count("size"))
     {
-      opts.max_size = vm["size"].as<int>() * 1048576;
+      opts.max_size = vm["size"].as<uint64_t>() * 1048576;
       if (opts.max_size <= 0)
         throw ros::Exception("Split size must be 0 or positive");
     }
diff --git a/tools/rosbag/src/recorder.cpp b/tools/rosbag/src/recorder.cpp
index a6b7e26..c0c4602 100644
--- a/tools/rosbag/src/recorder.cpp
+++ b/tools/rosbag/src/recorder.cpp
@@ -109,7 +109,9 @@ RecorderOptions::RecorderOptions() :
     split(false),
     max_size(0),
     max_duration(-1.0),
-    node("")
+    node(""),
+    min_space(1024 * 1024 * 1024),
+    min_space_str("1G")
 {
 }
 
@@ -393,6 +395,23 @@ void Recorder::stopWriting() {
     rename(write_filename_.c_str(), target_filename_.c_str());
 }
 
+void Recorder::checkNumSplits()
+{
+    if(options_.max_splits>0)
+    {
+        current_files_.push_back(target_filename_);
+        if(current_files_.size()>options_.max_splits)
+        {
+            int err = unlink(current_files_.front().c_str());
+            if(err != 0)
+            {
+                ROS_ERROR("Unable to remove %s: %s", current_files_.front().c_str(), strerror(errno));
+            }
+            current_files_.pop_front();
+        }
+    }
+}
+
 bool Recorder::checkSize()
 {
     if (options_.max_size > 0)
@@ -403,6 +422,7 @@ bool Recorder::checkSize()
             {
                 stopWriting();
                 split_count_++;
+                checkNumSplits();
                 startWriting();
             } else {
                 ros::shutdown();
@@ -425,6 +445,7 @@ bool Recorder::checkDuration(const ros::Time& t)
                 {
                     stopWriting();
                     split_count_++;
+                    checkNumSplits();
                     start_time_ += options_.max_duration;
                     startWriting();
                 }
diff --git a/tools/rosbag/src/rosbag/rosbag_main.py b/tools/rosbag/src/rosbag/rosbag_main.py
index f75a496..e434860 100644
--- a/tools/rosbag/src/rosbag/rosbag_main.py
+++ b/tools/rosbag/src/rosbag/rosbag_main.py
@@ -77,6 +77,7 @@ def record_cmd(argv):
     parser.add_option("-o", "--output-prefix", dest="prefix",        default=None,  action="store",               help="prepend PREFIX to beginning of bag name (name will always end with date stamp)")
     parser.add_option("-O", "--output-name",   dest="name",          default=None,  action="store",               help="record to bag with name NAME.bag")
     parser.add_option(      "--split",         dest="split",         default=False, callback=handle_split, action="callback",    help="split the bag when maximum size or duration is reached")
+    parser.add_option(      "--max-splits",    dest="max_splits",                   type='int',   action="store", help="Keep a maximum of N bag files, when reaching the maximum erase the oldest one to keep a constant number of files.", metavar="MAX_SPLITS")
     parser.add_option(      "--size",          dest="size",                         type='int',   action="store", help="record a bag of maximum size SIZE MB. (Default: infinite)", metavar="SIZE")
     parser.add_option(      "--duration",      dest="duration",                     type='string',action="store", help="record a bag of maximum duration DURATION in seconds, unless 'm', or 'h' is appended.", metavar="DURATION")
     parser.add_option("-b", "--buffsize",      dest="buffsize",      default=256,   type='int',   action="store", help="use an internal buffer of SIZE MB (Default: %default, 0 = infinite)", metavar="SIZE")
@@ -114,6 +115,8 @@ def record_cmd(argv):
         if not options.duration and not options.size:
             parser.error("Split specified without giving a maximum duration or size")
         cmd.extend(["--split"])
+        if options.max_splits:
+            cmd.extend(["--max-splits", str(options.max_splits)])
     if options.duration:    cmd.extend(["--duration", options.duration])
     if options.size:        cmd.extend(["--size", str(options.size)])
     if options.node:
@@ -304,7 +307,7 @@ The following variables are available:
         return
 
     try:
-        meter = ProgressMeter(outbag_filename, inbag.size)
+        meter = ProgressMeter(outbag_filename, inbag._uncompressed_size)
         total_bytes = 0
     
         if options.verbose_pattern:
diff --git a/tools/rosbag_storage/CHANGELOG.rst b/tools/rosbag_storage/CHANGELOG.rst
index c7fe6f4..d6febc0 100644
--- a/tools/rosbag_storage/CHANGELOG.rst
+++ b/tools/rosbag_storage/CHANGELOG.rst
@@ -2,6 +2,10 @@
 Changelog for package rosbag_storage
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.12.3 (2016-09-17)
+-------------------
+* make Bag constructor explicit (`#835 <https://github.com/ros/ros_comm/pull/835>`_)
+
 1.12.2 (2016-06-03)
 -------------------
 
diff --git a/tools/rosbag_storage/include/rosbag/bag.h b/tools/rosbag_storage/include/rosbag/bag.h
index 0696d72..e8a346e 100644
--- a/tools/rosbag_storage/include/rosbag/bag.h
+++ b/tools/rosbag_storage/include/rosbag/bag.h
@@ -95,7 +95,7 @@ public:
      *
      * Can throw BagException
      */
-    Bag(std::string const& filename, uint32_t mode = bagmode::Read);
+    explicit Bag(std::string const& filename, uint32_t mode = bagmode::Read);
 
     ~Bag();
 
diff --git a/tools/rosbag_storage/package.xml b/tools/rosbag_storage/package.xml
index 24aae63..d7c38c6 100644
--- a/tools/rosbag_storage/package.xml
+++ b/tools/rosbag_storage/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>rosbag_storage</name>
-  <version>1.12.2</version>
+  <version>1.12.3</version>
   <description>
     This is a set of tools for recording from and playing back ROS
     message without relying on the ROS client library.
diff --git a/tools/rosconsole/CHANGELOG.rst b/tools/rosconsole/CHANGELOG.rst
index 8a0d481..1fffd50 100644
--- a/tools/rosconsole/CHANGELOG.rst
+++ b/tools/rosconsole/CHANGELOG.rst
@@ -2,6 +2,9 @@
 Changelog for package rosconsole
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.12.3 (2016-09-17)
+-------------------
+
 1.12.2 (2016-06-03)
 -------------------
 
diff --git a/tools/rosconsole/package.xml b/tools/rosconsole/package.xml
index cf6ccdf..5db9161 100644
--- a/tools/rosconsole/package.xml
+++ b/tools/rosconsole/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>rosconsole</name>
-  <version>1.12.2</version>
+  <version>1.12.3</version>
   <description>ROS console output library.</description>
   <maintainer email="dthomas at osrfoundation.org">Dirk Thomas</maintainer>
   <license>BSD</license>
diff --git a/tools/rosgraph/CHANGELOG.rst b/tools/rosgraph/CHANGELOG.rst
index 64e964c..19c1ac2 100644
--- a/tools/rosgraph/CHANGELOG.rst
+++ b/tools/rosgraph/CHANGELOG.rst
@@ -2,6 +2,12 @@
 Changelog for package rosgraph
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.12.3 (2016-09-17)
+-------------------
+* add 'Darwin' to unix-like platforms improving address resolution (`#846 <https://github.com/ros/ros_comm/pull/846>`_)
+* use logging Formatter, enabling printing exception info with exc_info=1 (`#828 <https://github.com/ros/ros_comm/pull/828>`_)
+* add `__contains_\_`, which is a better spelling of `has` (`#754 <https://github.com/ros/ros_comm/pull/754>`_)
+
 1.12.2 (2016-06-03)
 -------------------
 * avoid creating a latest symlink for the root of the log dir (`#795 <https://github.com/ros/ros_comm/pull/795>`_)
diff --git a/tools/rosgraph/package.xml b/tools/rosgraph/package.xml
index e05fe74..dbad776 100644
--- a/tools/rosgraph/package.xml
+++ b/tools/rosgraph/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>rosgraph</name>
-  <version>1.12.2</version>
+  <version>1.12.3</version>
   <description>
     rosgraph contains the rosgraph command-line tool, which prints
     information about the ROS Computation Graph. It also provides an
diff --git a/tools/rosgraph/src/rosgraph/impl/graph.py b/tools/rosgraph/src/rosgraph/impl/graph.py
index 3929da7..c96e20e 100644
--- a/tools/rosgraph/src/rosgraph/impl/graph.py
+++ b/tools/rosgraph/src/rosgraph/impl/graph.py
@@ -104,6 +104,9 @@ class EdgeList(object):
         return itertools.chain(*[v for v in self.edges_by_start.values()])
     
     def has(self, edge):
+        return edge in self
+
+    def __contains__(self, edge):
         """
         @return: True if edge is in edge list
         @rtype: bool
diff --git a/tools/rosgraph/src/rosgraph/network.py b/tools/rosgraph/src/rosgraph/network.py
index 35c35ed..0d42277 100644
--- a/tools/rosgraph/src/rosgraph/network.py
+++ b/tools/rosgraph/src/rosgraph/network.py
@@ -101,8 +101,7 @@ def _is_unix_like_platform():
     :returns: true if the platform conforms to UNIX/POSIX-style APIs
     @rtype: bool
     """
-    #return platform.system() in ['Linux', 'Mac OS X', 'Darwin']
-    return platform.system() in ['Linux', 'FreeBSD']
+    return platform.system() in ['Linux', 'FreeBSD', 'Darwin']
 
 def get_address_override():
     """
diff --git a/tools/rosgraph/src/rosgraph/roslogging.py b/tools/rosgraph/src/rosgraph/roslogging.py
index bc9aace..2f0a7cd 100644
--- a/tools/rosgraph/src/rosgraph/roslogging.py
+++ b/tools/rosgraph/src/rosgraph/roslogging.py
@@ -157,6 +157,7 @@ _logging_to_rospy_names = {
     'CRITICAL': ('FATAL', '\033[31m')
 }
 _color_reset = '\033[0m'
+_defaultFormatter = logging.Formatter()
 
 class RosStreamHandler(logging.Handler):
     def __init__(self, colorize=True):
@@ -172,10 +173,11 @@ class RosStreamHandler(logging.Handler):
 
     def emit(self, record):
         level, color = _logging_to_rospy_names[record.levelname]
+        record_message = _defaultFormatter.format(record)
         if 'ROSCONSOLE_FORMAT' in os.environ.keys():
             msg = os.environ['ROSCONSOLE_FORMAT']
             msg = msg.replace('${severity}', level)
-            msg = msg.replace('${message}', str(record.getMessage()))
+            msg = msg.replace('${message}', str(record_message))
             msg = msg.replace('${walltime}', '%f' % time.time())
             msg = msg.replace('${thread}', str(record.thread))
             msg = msg.replace('${logger}', str(record.name))
@@ -198,7 +200,7 @@ class RosStreamHandler(logging.Handler):
             msg = '[%s] [WallTime: %f]' % (level, time.time())
             if self._get_time is not None and not self._is_wallclock():
                 msg += ' [%f]' % self._get_time()
-            msg += ' %s\n' % record.getMessage()
+            msg += ' %s\n' % record_message
         if record.levelno < logging.WARNING:
             self._write(sys.stdout, msg, color)
         else:
diff --git a/tools/roslaunch/CHANGELOG.rst b/tools/roslaunch/CHANGELOG.rst
index 3eacdf5..7f9e434 100644
--- a/tools/roslaunch/CHANGELOG.rst
+++ b/tools/roslaunch/CHANGELOG.rst
@@ -2,6 +2,13 @@
 Changelog for package roslaunch
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.12.3 (2016-09-17)
+-------------------
+* better naming for roslaunch check test results (`#897 <https://github.com/ros/ros_comm/pull/897>`_)
+* support use_test_depends option for roslaunch-check (`#887 <https://github.com/ros/ros_comm/pull/887>`_)
+* allow empty include (`#882 <https://github.com/ros/ros_comm/pull/882>`_)
+* fix param command for Python 3 (`#840 <https://github.com/ros/ros_comm/pull/840>`_)
+
 1.12.2 (2016-06-03)
 -------------------
 * support registering the same test multiple times with different arguments (`#814 <https://github.com/ros/ros_comm/pull/814>`_)
diff --git a/tools/roslaunch/package.xml b/tools/roslaunch/package.xml
index b766136..40b2e6b 100644
--- a/tools/roslaunch/package.xml
+++ b/tools/roslaunch/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>roslaunch</name>
-  <version>1.12.2</version>
+  <version>1.12.3</version>
   <description>
     roslaunch is a tool for easily launching multiple ROS <a
     href="http://ros.org/wiki/Nodes">nodes</a> locally and remotely
@@ -29,7 +29,7 @@
   <run_depend version_gte="1.11.16">rosmaster</run_depend>
   <run_depend>rosout</run_depend>
   <run_depend>rosparam</run_depend>
-  <run_depend>rosunit</run_depend>
+  <run_depend version_gte="1.13.3">rosunit</run_depend>
 
   <test_depend>rosbuild</test_depend>
 
diff --git a/tools/roslaunch/scripts/roslaunch-check b/tools/roslaunch/scripts/roslaunch-check
index a69b00d..c91bad5 100755
--- a/tools/roslaunch/scripts/roslaunch-check
+++ b/tools/roslaunch/scripts/roslaunch-check
@@ -41,20 +41,20 @@ import rospkg
 import roslaunch.rlutil
 import rosunit
 
-def check_roslaunch_file(roslaunch_file):
+def check_roslaunch_file(roslaunch_file, use_test_depends=False):
     print("checking", roslaunch_file)
-    error_msg = roslaunch.rlutil.check_roslaunch(roslaunch_file)
+    error_msg = roslaunch.rlutil.check_roslaunch(roslaunch_file, use_test_depends=use_test_depends)
     # error message has to be XML attr safe
     if error_msg:
         return "[%s]:\n\t%s"%(roslaunch_file,error_msg)
 
-def check_roslaunch_dir(roslaunch_dir):
+def check_roslaunch_dir(roslaunch_dir, use_test_depends=False):
     error_msgs = []
     for f in os.listdir(roslaunch_dir):
         if f.endswith('.launch'):
             roslaunch_file = os.path.join(roslaunch_dir, f)
             if os.path.isfile(roslaunch_file):
-                error_msgs.append(check_roslaunch_file(roslaunch_file))
+                error_msgs.append(check_roslaunch_file(roslaunch_file, use_test_depends=use_test_depends))
     # error message has to be XML attr safe
     return '\n'.join([e for e in error_msgs if e])
 
@@ -66,6 +66,9 @@ if __name__ == '__main__':
     parser.add_option("-o", "--output-file",
                       dest="output_file", default=None,
                       help="file to store test results in", metavar="FILE")
+    parser.add_option("-t", "--use-test-depends",
+                      action="store_true", dest="test_depends", default=False,
+                      help="Assuming packages listed in test_depends are also installed")
 
     options, args = parser.parse_args()
     if not args:
@@ -83,16 +86,14 @@ if __name__ == '__main__':
     pkg_dir = r.get_path(pkg)
 
     if os.path.isfile(roslaunch_path):
-        error_msg = check_roslaunch_file(roslaunch_path)
-        outname = os.path.basename(roslaunch_path).replace('.', '_')
+        error_msg = check_roslaunch_file(roslaunch_path, use_test_depends=options.test_depends)
     else:
         print("checking *.launch in directory", roslaunch_path)
-        error_msg = check_roslaunch_dir(roslaunch_path)
-        abspath = os.path.abspath
-        relpath = abspath(roslaunch_path)[len(abspath(pkg_dir))+1:]
-        outname = relpath.replace(os.sep, '_')
-        if outname == '.':
-            outname = '_pkg'
+        error_msg = check_roslaunch_dir(roslaunch_path, use_test_depends=options.test_depends)
+    relpath = os.path.abspath(roslaunch_path)[len(os.path.abspath(pkg_dir))+1:]
+    outname = relpath.replace('.', '_').replace(os.sep, '_')
+    if outname == '_':
+        outname = '_pkg'
 
     if options.output_file:
         test_file = options.output_file
@@ -113,10 +114,12 @@ if __name__ == '__main__':
         print("FAILURE:\n%s"%error_msg, file=sys.stderr)
         with open(test_file, 'w') as f:
             message = "roslaunch check [%s] failed"%(roslaunch_path)
-            f.write(rosunit.junitxml.test_failure_junit_xml(test_name, message, stdout=error_msg))
+            f.write(rosunit.junitxml.test_failure_junit_xml(test_name, message, stdout=error_msg,
+                    class_name="roslaunch.RoslaunchCheck", testcase_name="%s_%s" % (pkg, outname)))
         print("wrote test file to [%s]"%test_file)
         sys.exit(1)
     else:
         print("passed")
         with open(test_file, 'w') as f:
-            f.write(rosunit.junitxml.test_success_junit_xml(test_name))
+            f.write(rosunit.junitxml.test_success_junit_xml(test_name,
+                    class_name="roslaunch.RoslaunchCheck", testcase_name="%s_%s" % (pkg, outname)))
diff --git a/tools/roslaunch/src/roslaunch/depends.py b/tools/roslaunch/src/roslaunch/depends.py
index b4c7fd7..2cb8a75 100644
--- a/tools/roslaunch/src/roslaunch/depends.py
+++ b/tools/roslaunch/src/roslaunch/depends.py
@@ -146,7 +146,15 @@ def _parse_launch(tags, launch_file, file_deps, verbose, context):
                 sub_launch_file = resolve_args(tag.attributes['file'].value, context)
             except KeyError as e:
                 raise RoslaunchDepsException("Cannot load roslaunch <%s> tag: missing required attribute %s.\nXML is %s"%(tag.tagName, str(e), tag.toxml()))
-                
+
+            # Check if an empty file is included, and skip if so.
+            # This will allow a default-empty <include> inside a conditional to pass
+            if sub_launch_file == '':
+                if verbose:
+                    print("Empty <include> in %s. Skipping <include> of %s" %
+                          (launch_file, tag.attributes['file'].value))
+                continue
+
             if verbose:
                 print("processing included launch %s"%sub_launch_file)
 
@@ -245,7 +253,7 @@ def print_deps(base_pkg, file_deps, verbose):
     # print space-separated to be friendly to rosmake
     print(' '.join([p for p in set(pkgs)]))
 
-def calculate_missing(base_pkg, missing, file_deps):
+def calculate_missing(base_pkg, missing, file_deps, use_test_depends=False):
     """
     Calculate missing package dependencies in the manifest. This is
     mainly used as a subroutine of roslaunch_deps().
@@ -256,6 +264,8 @@ def calculate_missing(base_pkg, missing, file_deps):
     @type  missing: { str: set(str) }
     @param file_deps: dictionary mapping launch file names to RoslaunchDeps of each file
     @type  file_deps: { str: RoslaunchDeps}
+    @param use_test_depends [bool]: use test_depends as installed package
+    @type  use_test_depends: [bool]
     @return: missing (see parameter)
     @rtype: { str: set(str) }
     """
@@ -275,6 +285,9 @@ def calculate_missing(base_pkg, missing, file_deps):
             from catkin_pkg.package import parse_package
             p = parse_package(os.path.dirname(m.filename))
             d_pkgs = set([d.name for d in p.run_depends])
+            if use_test_depends:
+                for d in p.test_depends:
+                    d_pkgs.add(d.name)
         # make sure we don't count ourselves as a dep
         d_pkgs.add(pkg)
 
@@ -285,13 +298,15 @@ def calculate_missing(base_pkg, missing, file_deps):
     return missing
         
     
-def roslaunch_deps(files, verbose=False):
+def roslaunch_deps(files, verbose=False, use_test_depends=False):
     """
     @param packages: list of packages to check
     @type  packages: [str]
     @param files [str]: list of roslaunch files to check. Must be in
       same package.
     @type  files: [str]
+    @param use_test_depends [bool]: use test_depends as installed package
+    @type  use_test_depends: [bool]
     @return: base_pkg, file_deps, missing.
       base_pkg is the package of all files
       file_deps is a { filename : RoslaunchDeps } dictionary of
@@ -315,7 +330,7 @@ def roslaunch_deps(files, verbose=False):
         base_pkg = pkg
         rl_file_deps(file_deps, launch_file, verbose)
 
-    calculate_missing(base_pkg, missing, file_deps)
+    calculate_missing(base_pkg, missing, file_deps, use_test_depends=use_test_depends)
     return base_pkg, file_deps, missing            
     
 def roslaunch_deps_main(argv=sys.argv):
diff --git a/tools/roslaunch/src/roslaunch/loader.py b/tools/roslaunch/src/roslaunch/loader.py
index db8e6c7..dac9ac4 100644
--- a/tools/roslaunch/src/roslaunch/loader.py
+++ b/tools/roslaunch/src/roslaunch/loader.py
@@ -479,7 +479,7 @@ class Loader(object):
         elif command is not None:
             try:
                 if type(command) == unicode:
-                    command = command.encode('UTF-8') #attempt to force to string for shlex/subprocess
+                    command = command.encode('utf-8') #attempt to force to string for shlex/subprocess
             except NameError:
                 pass
             if verbose:
@@ -488,6 +488,8 @@ class Loader(object):
             try:
                 p = subprocess.Popen(shlex.split(command), stdout=subprocess.PIPE)
                 c_value = p.communicate()[0]
+                if not isinstance(c_value, str):
+                    c_value = c_value.decode('utf-8')
                 if p.returncode != 0:
                     raise ValueError("Cannot load command parameter [%s]: command [%s] returned with code [%s]"%(name, command, p.returncode))
             except OSError as e:
diff --git a/tools/roslaunch/src/roslaunch/rlutil.py b/tools/roslaunch/src/roslaunch/rlutil.py
index 9d4300a..d8fa809 100644
--- a/tools/roslaunch/src/roslaunch/rlutil.py
+++ b/tools/roslaunch/src/roslaunch/rlutil.py
@@ -180,12 +180,13 @@ def get_or_generate_uuid(options_runid, options_wait_for_master):
                 val = roslaunch.core.generate_run_id()
     return val
     
-def check_roslaunch(f):
+def check_roslaunch(f, use_test_depends=False):
     """
     Check roslaunch file for errors, returning error message if check fails. This routine
     is mainly to support rostest's roslaunch_check.
 
     :param f: roslaunch file name, ``str``
+    :param use_test_depends: Consider test_depends, ``Bool``
     :returns: error message or ``None``
     """
     try:
@@ -197,7 +198,7 @@ def check_roslaunch(f):
     errors = []
     # check for missing deps
     try:
-        base_pkg, file_deps, missing = roslaunch.depends.roslaunch_deps([f])
+        base_pkg, file_deps, missing = roslaunch.depends.roslaunch_deps([f], use_test_depends=use_test_depends)
     except rospkg.common.ResourceNotFound as r:
         errors.append("Could not find package [%s] included from [%s]"%(str(r), f))
         missing = {}
diff --git a/tools/rosmaster/CHANGELOG.rst b/tools/rosmaster/CHANGELOG.rst
index f0b3fa2..94266de 100644
--- a/tools/rosmaster/CHANGELOG.rst
+++ b/tools/rosmaster/CHANGELOG.rst
@@ -2,6 +2,9 @@
 Changelog for package rosmaster
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.12.3 (2016-09-17)
+-------------------
+
 1.12.2 (2016-06-03)
 -------------------
 
diff --git a/tools/rosmaster/package.xml b/tools/rosmaster/package.xml
index 12d62e0..9837aff 100644
--- a/tools/rosmaster/package.xml
+++ b/tools/rosmaster/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>rosmaster</name>
-  <version>1.12.2</version>
+  <version>1.12.3</version>
   <description>
     ROS <a href="http://ros.org/wiki/Master">Master</a> implementation.
   </description>
diff --git a/tools/rosmsg/CHANGELOG.rst b/tools/rosmsg/CHANGELOG.rst
index 8aaa8e0..cff1491 100644
--- a/tools/rosmsg/CHANGELOG.rst
+++ b/tools/rosmsg/CHANGELOG.rst
@@ -2,6 +2,10 @@
 Changelog for package rosmsg
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.12.3 (2016-09-17)
+-------------------
+* register nosetests only when testing is enabled (`#880 <https://github.com/ros/ros_comm/issues/880>`_)
+
 1.12.2 (2016-06-03)
 -------------------
 
diff --git a/tools/rosmsg/CMakeLists.txt b/tools/rosmsg/CMakeLists.txt
index 4a50539..2445b71 100644
--- a/tools/rosmsg/CMakeLists.txt
+++ b/tools/rosmsg/CMakeLists.txt
@@ -4,3 +4,7 @@ find_package(catkin)
 catkin_package()
 
 catkin_python_setup()
+
+if(CATKIN_ENABLE_TESTING)
+  catkin_add_nosetests(test)
+endif()
diff --git a/tools/rosmsg/package.xml b/tools/rosmsg/package.xml
index 76343f1..3a99170 100644
--- a/tools/rosmsg/package.xml
+++ b/tools/rosmsg/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>rosmsg</name>
-  <version>1.12.2</version>
+  <version>1.12.3</version>
   <description>
     rosmsg contains two command-line tools: <tt>rosmsg</tt> and
     <tt>rossrv</tt>. <tt>rosmsg</tt> is a command-line tool for
@@ -25,6 +25,8 @@
   <run_depend>rosbag</run_depend>
   <run_depend>roslib</run_depend>
 
+  <test_depend>std_msgs</test_depend>
+
   <export>
     <rosdoc config="rosdoc.yaml"/>
     <architecture_independent/>
diff --git a/tools/rosmsg/test/RosmsgC_raw.txt b/tools/rosmsg/test/RosmsgC_raw.txt
new file mode 100644
index 0000000..6d4301a
--- /dev/null
+++ b/tools/rosmsg/test/RosmsgC_raw.txt
@@ -0,0 +1,4 @@
+test_rosmaster/String s1
+  string data
+test_rosmaster/String s2
+  string data
diff --git a/tools/rosmsg/test/msg/RosmsgB.msg b/tools/rosmsg/test/msg/RosmsgB.msg
index 2f11e66..9ea4919 100644
--- a/tools/rosmsg/test/msg/RosmsgB.msg
+++ b/tools/rosmsg/test/msg/RosmsgB.msg
@@ -1 +1 @@
-std_msgs/Empty empty
+test_rosmaster/Empty empty
diff --git a/tools/rosmsg/test/msg/RosmsgC.msg b/tools/rosmsg/test/msg/RosmsgC.msg
deleted file mode 100644
index 634cba2..0000000
--- a/tools/rosmsg/test/msg/RosmsgC.msg
+++ /dev/null
@@ -1,2 +0,0 @@
-std_msgs/String s1
-std_msgs/String s2
diff --git a/tools/rosmsg/test/srv/RossrvB.srv b/tools/rosmsg/test/srv/RossrvB.srv
index 07d485e..575e100 100644
--- a/tools/rosmsg/test/srv/RossrvB.srv
+++ b/tools/rosmsg/test/srv/RossrvB.srv
@@ -1,3 +1,3 @@
-std_msgs/Empty empty
+test_rosmaster/Empty empty
 ---
-std_msgs/Empty empty
+test_rosmaster/Empty empty
diff --git a/tools/rosmsg/test/test_rosmsg.py b/tools/rosmsg/test/test_rosmsg.py
index 61ad986..039f342 100644
--- a/tools/rosmsg/test/test_rosmsg.py
+++ b/tools/rosmsg/test/test_rosmsg.py
@@ -39,6 +39,8 @@ try:
 except ImportError:
     from io import StringIO
 import time
+
+import rospkg
         
 import rosmsg
 
@@ -66,23 +68,30 @@ class TestRosmsg(unittest.TestCase):
     def test_get_msg_text(self):
         d = get_test_path()
         msg_d = os.path.join(d, 'msg')
+        
+        test_message_package = 'test_rosmaster'
+        rospack = rospkg.RosPack()
+        msg_raw_d = os.path.join(rospack.get_path(test_message_package), 'msg')
         for t in ['RosmsgA', 'RosmsgB']:
             with open(os.path.join(msg_d, '%s.msg'%t), 'r') as f:
                 text = f.read()
-            type_ = 'test_ros/'+t
+            with open(os.path.join(msg_raw_d, '%s.msg'%t), 'r') as f:
+                text_raw = f.read()
+                
+            type_ = test_message_package+'/'+t
             self.assertEquals(text, rosmsg.get_msg_text(type_, raw=False))
-            self.assertEquals(text, rosmsg.get_msg_text(type_, raw=True))
+            self.assertEquals(text_raw, rosmsg.get_msg_text(type_, raw=True))
             
         # test recursive types
         t = 'RosmsgC'
-        with open(os.path.join(msg_d, '%s.msg'%t), 'r') as f:
+        with open(os.path.join(d, '%s_raw.txt'%t), 'r') as f:
             text = f.read()
-        type_ = 'test_ros/'+t
-        self.assertEquals(text, rosmsg.get_msg_text(type_, raw=True))
-        self.assertEquals("""std_msgs/String s1
-  string data
-std_msgs/String s2
-  string data""", rosmsg.get_msg_text(type_, raw=False).strip())
+        with open(os.path.join(msg_raw_d, '%s.msg'%t), 'r') as f:
+            text_raw = f.read()
+        type_ = test_message_package+'/'+t
+        
+        self.assertEquals(text, rosmsg.get_msg_text(type_, raw=False))
+        self.assertEquals(text_raw, rosmsg.get_msg_text(type_, raw=True))
 
     def test_iterate_packages(self):
         from rosmsg import iterate_packages, MODE_MSG, MODE_SRV
@@ -111,29 +120,32 @@ std_msgs/String s2
         # test msgs
         l = rosmsg.list_types('rospy', mode='.msg')
         self.assertEquals([], l)
-        l = rosmsg.list_types('test_ros', mode='.msg')
-        for t in ['test_ros/RosmsgA', 'test_ros/RosmsgB', 'test_ros/RosmsgC']:
+        l = rosmsg.list_types('test_rosmaster', mode='.msg')
+        for t in ['test_rosmaster/RosmsgA', 'test_rosmaster/RosmsgB', 'test_rosmaster/RosmsgC']:
             assert t in l
         
         l = rosmsg.list_types('rospy', mode='.srv')
         self.assertEquals([], l)        
-        l = rosmsg.list_types('test_ros', mode='.srv')
-        for t in ['test_ros/RossrvA', 'test_ros/RossrvB']:
+        l = rosmsg.list_types('test_rosmaster', mode='.srv')
+        for t in ['test_rosmaster/RossrvA', 'test_rosmaster/RossrvB']:
             assert t in l
 
     def test_get_srv_text(self):
         d = get_test_path()
         srv_d = os.path.join(d, 'srv')
-        with open(os.path.join(srv_d, 'RossrvA.srv'), 'r') as f:
-            text = f.read()
-        self.assertEquals(text, rosmsg.get_srv_text('test_ros/RossrvA', raw=False))
-        self.assertEquals(text, rosmsg.get_srv_text('test_ros/RossrvA', raw=True))
-
-        # std_msgs/empty / std_msgs/empty
-        with open(os.path.join(srv_d, 'RossrvB.srv'), 'r') as f:
-            text = f.read()
-        self.assertEquals(text, rosmsg.get_srv_text('test_ros/RossrvB', raw=False))
-        self.assertEquals(text, rosmsg.get_srv_text('test_ros/RossrvB', raw=True))
+        
+        test_srv_package = 'test_rosmaster'
+        rospack = rospkg.RosPack()
+        srv_raw_d = os.path.join(rospack.get_path(test_srv_package), 'srv')
+        for t in ['RossrvA', 'RossrvB']:
+            with open(os.path.join(srv_d, '%s.srv'%t), 'r') as f:
+                text = f.read()
+            with open(os.path.join(srv_raw_d, '%s.srv'%t), 'r') as f:
+                text_raw = f.read()
+                
+            type_ = test_srv_package+'/'+t
+            self.assertEquals(text, rosmsg.get_srv_text(type_, raw=False))
+            self.assertEquals(text_raw, rosmsg.get_srv_text(type_, raw=True))
 
     def test_rosmsg_cmd_packages(self):
         from rosmsg import rosmsg_cmd_packages, MODE_MSG, MODE_SRV
diff --git a/tools/rosmsg/test/test_rosmsg_command_line.py b/tools/rosmsg/test/test_rosmsg_command_line.py
index 2097ba1..02e3102 100644
--- a/tools/rosmsg/test/test_rosmsg_command_line.py
+++ b/tools/rosmsg/test/test_rosmsg_command_line.py
@@ -75,7 +75,7 @@ class TestRosmsg(unittest.TestCase):
         l1 = [x for x in output1.split() if x]
         l2 = [x.strip() for x in output2.split('\n') if x.strip()]
         self.assertEquals(l1, l2)
-        for p in ['std_msgs', 'test_ros']:
+        for p in ['std_msgs', 'test_rosmaster']:
             self.assert_(p in l1)
         for p in ['std_srvs', 'rosmsg']:
             self.assert_(p not in l1)
@@ -85,7 +85,7 @@ class TestRosmsg(unittest.TestCase):
         l1 = [x for x in output1.split() if x]
         l2 = [x.strip() for x in output2.split('\n') if x.strip()]
         self.assertEquals(l1, l2)
-        for p in ['std_srvs', 'test_ros']:
+        for p in ['std_srvs', 'test_rosmaster']:
             self.assert_(p in l1)
         for p in ['std_msgs', 'rospy']:
             self.assert_(p not in l1)
@@ -94,7 +94,7 @@ class TestRosmsg(unittest.TestCase):
         # - multi-line
         output1 = Popen([os.path.join(_SCRIPT_FOLDER,'rosmsg'), 'list'], stdout=PIPE).communicate()[0]
         l1 = [x.strip() for x in output1.split('\n') if x.strip()]
-        for p in ['std_msgs/String', 'test_ros/Floats']:
+        for p in ['std_msgs/String', 'test_rosmaster/Floats']:
             self.assert_(p in l1)
         for p in ['std_srvs/Empty', 'roscpp/Empty']:
             self.assert_(p not in l1)
@@ -103,31 +103,31 @@ class TestRosmsg(unittest.TestCase):
         l1 = [x.strip() for x in output1.split('\n') if x.strip()]
         for p in ['std_srvs/Empty', 'roscpp/Empty']:
             self.assert_(p in l1)
-        for p in ['std_msgs/String', 'test_ros/Floats']:
+        for p in ['std_msgs/String', 'test_rosmaster/Floats']:
             self.assert_(p not in l1)
         
     def test_cmd_package(self):
         # this test is obviously very brittle, but should stabilize as the tests stabilize
         # - single line output
-        output1 = Popen(['rosmsg', 'package', '-s', 'test_ros'], stdout=PIPE).communicate()[0]
+        output1 = Popen(['rosmsg', 'package', '-s', 'test_rosmaster'], stdout=PIPE).communicate()[0]
         # - multi-line output
-        output2 = Popen(['rosmsg', 'package', 'test_ros'], stdout=PIPE).communicate()[0]
+        output2 = Popen(['rosmsg', 'package', 'test_rosmaster'], stdout=PIPE).communicate()[0]
         l = set([x for x in output1.split() if x])        
         l2 = set([x.strip() for x in output2.split('\n') if x.strip()])
         self.assertEquals(l, l2)
         
-        for m in ['test_ros/RosmsgA',
-                  'test_ros/RosmsgB',
-                  'test_ros/RosmsgC']:
+        for m in ['test_rosmaster/RosmsgA',
+                  'test_rosmaster/RosmsgB',
+                  'test_rosmaster/RosmsgC']:
             self.assertTrue(m in l, l)
         
-        output = Popen(['rossrv', 'package', '-s', 'test_ros'], stdout=PIPE).communicate()[0]
-        output2 = Popen(['rossrv', 'package','test_ros'], stdout=PIPE).communicate()[0]        
+        output = Popen(['rossrv', 'package', '-s', 'test_rosmaster'], stdout=PIPE).communicate()[0]
+        output2 = Popen(['rossrv', 'package','test_rosmaster'], stdout=PIPE).communicate()[0]        
         l = set([x for x in output.split() if x])
         l2 = set([x.strip() for x in output2.split('\n') if x.strip()])
         self.assertEquals(l, l2)
         
-        for m in ['test_ros/RossrvA', 'test_ros/RossrvB']:
+        for m in ['test_rosmaster/RossrvA', 'test_rosmaster/RossrvB']:
             self.assertTrue(m in l, l)
         
     ## test that the rosmsg/rossrv show command works
@@ -139,32 +139,40 @@ class TestRosmsg(unittest.TestCase):
         self.assertEquals('---', output.strip())
         output = Popen(['rossrv', 'show', 'std_srvs/Empty'], stdout=PIPE).communicate()[0]
         self.assertEquals('---', output.strip())
-        output = Popen(['rossrv', 'show', 'test_ros/AddTwoInts'], stdout=PIPE).communicate()[0]
+        output = Popen(['rossrv', 'show', 'test_rosmaster/AddTwoInts'], stdout=PIPE).communicate()[0]
         self.assertEquals('int64 a\nint64 b\n---\nint64 sum', output.strip())
 
         # test against test_rosmsg package
-        rospack = rospkg.RosPack()
-        d = rospack.get_path('test_ros')
+        d = os.path.abspath(os.path.dirname(__file__))
         msg_d = os.path.join(d, 'msg')
-        # - test with non-recursive types, which should have identical raw/non-raw
+        
+        test_message_package = 'test_rosmaster'
+        rospack = rospkg.RosPack()
+        msg_raw_d = os.path.join(rospack.get_path(test_message_package), 'msg')
+        
+        # - test with non-recursive types
         for t in ['RosmsgA', 'RosmsgB']:
             with open(os.path.join(msg_d, '%s.msg'%t), 'r') as f:
                 text = f.read()
+            with open(os.path.join(msg_raw_d, '%s.msg'%t), 'r') as f:
+                text_raw = f.read()
             text = text+'\n' # running command adds one new line
-            type_ ='test_ros/'+t
+            text_raw = text_raw+'\n'
+            type_ =test_message_package+'/'+t
             output = Popen(['rosmsg', 'show', type_], stdout=PIPE).communicate()[0]
             self.assertEquals(text, output)
-            output = Popen(['rosmsg', 'show', '-r',type_], stdout=PIPE, stderr=PIPE).communicate()
-            self.assertEquals(text, output[0], "Failed: %s"%(str(output)))
+            output = Popen(['rosmsg', 'show', '-r',type_], stdout=PIPE).communicate()[0]
+            self.assertEquals(text_raw, output)
             output = Popen(['rosmsg', 'show', '--raw', type_], stdout=PIPE).communicate()[0]
-            self.assertEquals(text, output)
+            self.assertEquals(text_raw, output)
 
             # test as search
             type_ = t
-            text = "[test_ros/%s]:\n%s"%(t, text)
+            text = "[test_rosmaster/%s]:\n%s"%(t, text)
+            text_raw = "[test_rosmaster/%s]:\n%s"%(t, text_raw)
             output = Popen(['rosmsg', 'show', type_], stdout=PIPE).communicate()[0]
             self.assertEquals(text, output)
             output = Popen(['rosmsg', 'show', '-r',type_], stdout=PIPE, stderr=PIPE).communicate()
-            self.assertEquals(text, output[0], "Failed: %s"%(str(output)))
+            self.assertEquals(text_raw, output[0], "Failed: %s"%(str(output)))
             output = Popen(['rosmsg', 'show', '--raw', type_], stdout=PIPE).communicate()[0]
-            self.assertEquals(text, output)
+            self.assertEquals(text_raw, output)
diff --git a/tools/rosmsg/test/test_rosmsgproto.py b/tools/rosmsg/test/test_rosmsgproto.py
index 25e6bda..56d9559 100644
--- a/tools/rosmsg/test/test_rosmsgproto.py
+++ b/tools/rosmsg/test/test_rosmsgproto.py
@@ -113,6 +113,21 @@ class RosMsgProtoTest(unittest.TestCase):
         self.assertEqual('"data:\n  secs: 0\n  nsecs: 0"', rosmsg_cmd_prototype(["msg", "std_msgs/Duration"]))
         self.assertEqual('"{data: {secs: 0, nsecs: 0}}"', rosmsg_cmd_prototype(["msg", "std_msgs/Duration", "-f1"]))
 
+    def test_rosmsg_cmd_prototype_std_msgs_ColorRGBA(self):
+        self.assertEqual('"r: 0.0\ng: 0.0\nb: 0.0\na: 0.0"', rosmsg_cmd_prototype(["msg", "std_msgs/ColorRGBA", "-f0"]))
 
+    def test_rosmsg_cmd_prototype_std_msgs_MultiArrayLayout(self):
+        self.assertEqual('"dim:\n- label: \'\'\n  size: 0\n  stride: 0\ndata_offset: 0"', rosmsg_cmd_prototype(["msg", "std_msgs/MultiArrayLayout"]))
+        self.assertEqual('"dim: []\ndata_offset: 0"', rosmsg_cmd_prototype(["msg", "std_msgs/MultiArrayLayout", "-e"]))
 
+    def test_rosmsg_cmd_prototype_std_msgs_Float64MultiArray(self):
+        self.assertEqual('"layout:\n  dim:\n  - label: \'\'\n    size: 0\n    stride: 0\n  data_offset: 0\ndata:\n- 0"', rosmsg_cmd_prototype(["msg", "std_msgs/Float64MultiArray"]))
+        self.assertEqual('"layout:\n  dim:\n  - label: \'\'\n    size: 0\n  data_offset: 0"', rosmsg_cmd_prototype(["msg", "std_msgs/Float64MultiArray", "-x", "stride,data"]))
 
+    def test_rosmsg_cmd_prototype_std_msgs_MultiArrayDimension(self):
+        self.assertEqual('"label: \'\'\nsize: 0\nstride: 0"', rosmsg_cmd_prototype(["msg", "std_msgs/MultiArrayDimension"]))
+
+    def test_rosmsg_cmd_prototype_std_msgs_Float32MultiArray(self):
+        self.assertEqual('"layout:\n  dim:\n  - label: \'\'\n    size: 0\n    stride: 0\n  data_offset: 0\ndata:\n- 0"', rosmsg_cmd_prototype(["msg", "std_msgs/Float32MultiArray"]))
+        self.assertEqual('"layout:\n  dim:\n  - label: \'\'\n    size: 0\n    stride: 0\n  data_offset: 0\ndata:\n- 0"', rosmsg_cmd_prototype(["msg", "std_msgs/Float32MultiArray", "-f0"]))
+        self.assertEqual('"{layout: {dim: [{label: \'\', size: 0, stride: 0}], data_offset: 0}, data: [0]}"', rosmsg_cmd_prototype(["msg", "std_msgs/Float32MultiArray", "-f1"]))
diff --git a/tools/rosmsg/test/test_rosmsgproto_geometry.py b/tools/rosmsg/test/test_rosmsgproto_geometry.py
deleted file mode 100644
index 27ba4d8..0000000
--- a/tools/rosmsg/test/test_rosmsgproto_geometry.py
+++ /dev/null
@@ -1,89 +0,0 @@
-#!/usr/bin/env python
-# Software License Agreement (BSD License)
-#
-# Copyright (c) 2011, Willow Garage, Inc.
-# All rights reserved.
-#
-# Redistribution and use in source and binary forms, with or without
-# modification, are permitted provided that the following conditions
-# are met:
-#
-#  * Redistributions of source code must retain the above copyright
-#    notice, this list of conditions and the following disclaimer.
-#  * Redistributions in binary form must reproduce the above
-#    copyright notice, this list of conditions and the following
-#    disclaimer in the documentation and/or other materials provided
-#    with the distribution.
-#  * Neither the name of Willow Garage, Inc. nor the names of its
-#    contributors may be used to endorse or promote products derived
-#    from this software without specific prior written permission.
-#
-# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
-# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
-# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
-# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
-# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
-# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
-# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
-# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
-# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
-# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
-# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
-# POSSIBILITY OF SUCH DAMAGE.
-
-# Author: Thibault Kruse
-
-from __future__ import with_statement
-NAME = 'test_rosmsgproto'
-
-import os
-import sys 
-import unittest
-import time
-import std_msgs
-
-import rostest
-
-import roslib.packages
-import rosmsg
-from rosmsg import *
-
-from nose.plugins.skip import SkipTest
-
-_NO_DICT=True
-if "OrderedDict" in collections.__dict__:
-    _NO_DICT=False
-
-class RosMsgProtoTest(unittest.TestCase):
-
-    def setUp(self):
-        # proto depends on python 2.7 having OrderedDict
-        if _NO_DICT: raise SkipTest("Test skipped because Python version too low")
-    
-    def test_rosmsg_cmd_prototype_geom_msgs_Pose(self):
-        self.assertEqual('"position:\n  x: 0.0\n  y: 0.0\n  z: 0.0\norientation:\n  x: 0.0\n  y: 0.0\n  z: 0.0\n  w: 0.0"', rosmsg_cmd_prototype(["msg", "geometry_msgs/Pose", "-f0"]))
-
-    def test_rosmsg_cmd_prototype_geom_msgs_PoseArray(self):
-        self.assertEqual('"header:\n  seq: 0\n  stamp:\n    secs: 0\n    nsecs: 0\n  frame_id: \'\'\nposes:\n- position:\n    x: 0.0\n    y: 0.0\n    z: 0.0\n  orientation:\n    x: 0.0\n    y: 0.0\n    z: 0.0\n    w: 0.0"', rosmsg_cmd_prototype(["msg", "geometry_msgs/PoseArray"]))
-        self.assertEqual('"header:\n  seq: 0\n  stamp:\n    secs: 0\n    nsecs: 0\n  frame_id: \'\'\nposes: []"', rosmsg_cmd_prototype(["msg", "geometry_msgs/PoseArray", "-e"]))
-        
-    def test_rosmsg_cmd_prototype_geom_msgs_PoseStamped(self):
-        self.assertEqual('"header:\n  seq: 0\n  stamp:\n    secs: 0\n    nsecs: 0\n  frame_id: \'\'\npose:\n  position:\n    x: 0.0\n    y: 0.0\n    z: 0.0\n  orientation:\n    x: 0.0\n    y: 0.0\n    z: 0.0\n    w: 0.0"', rosmsg_cmd_prototype(["msg", "geometry_msgs/PoseStamped"]))
-        self.assertEqual('"header:\n  frame_id: \'\'\npose:\n  position:\n    x: 0.0\n    y: 0.0\n    z: 0.0\n  orientation:\n    x: 0.0\n    y: 0.0\n    z: 0.0\n    w: 0.0"', rosmsg_cmd_prototype(["msg", "geometry_msgs/PoseStamped", "-x", "stamp,seq"]))
-
-    def test_rosmsg_cmd_prototype_geom_msgs_Transform(self):
-        self.assertEqual('"translation:\n  x: 0.0\n  y: 0.0\n  z: 0.0\nrotation:\n  x: 0.0\n  y: 0.0\n  z: 0.0\n  w: 0.0"', rosmsg_cmd_prototype(["msg", "geometry_msgs/Transform"]))
-
-    def test_rosmsg_cmd_prototype_geom_msgs_TransformStamped(self):
-        self.assertEqual('"header:\n  seq: 0\n  stamp:\n    secs: 0\n    nsecs: 0\n  frame_id: \'\'\nchild_frame_id: \'\'\ntransform:\n  translation:\n    x: 0.0\n    y: 0.0\n    z: 0.0\n  rotation:\n    x: 0.0\n    y: 0.0\n    z: 0.0\n    w: 0.0"', rosmsg_cmd_prototype(["msg", "geometry_msgs/TransformStamped"]))
-        self.assertEqual('"header:\n  seq: 0\n  stamp:\n    secs: 0\n    nsecs: 0\n  frame_id: \'\'\nchild_frame_id: \'\'\ntransform:\n  translation:\n    x: 0.0\n    y: 0.0\n    z: 0.0\n  rotation:\n    x: 0.0\n    y: 0.0\n    z: 0.0\n    w: 0.0"', rosmsg_cmd_prototype(["msg", "geometry_msgs/TransformStamped", "-f0"]))
-        self.assertEqual('"{header: {seq: 0, stamp: {secs: 0, nsecs: 0}, frame_id: \'\'}, child_frame_id: \'\', transform: {\n    translation: {x: 0.0, y: 0.0, z: 0.0}, rotation: {x: 0.0, y: 0.0, z: 0.0, w: 0.0}}}"', rosmsg_cmd_prototype(["msg", "geometry_msgs/TransformStamped", "-f1"]))
-
-    def test_rosmsg_cmd_prototype_geom_msgs_TwistWithCovariance(self):
-        self.assertEqual('"twist:\n  linear:\n    x: 0.0\n    y: 0.0\n    z: 0.0\n  angular:\n    x: 0.0\n    y: 0.0\n    z: 0.0\ncovariance:\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0"', rosmsg_cmd_prototype(["msg", "geometry_msgs/TwistWithCovariance", "-f0"]))
-        self.assertEqual('"twist:\n  linear:\n    x: 0.0\n    y: 0.0\n    z: 0.0\n  angular:\n    x: 0.0\n    y: 0.0\n    z: 0.0\ncovariance:\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0\n- 0.0"', rosmsg_cmd_prototype(["msg", "geometry_msgs/TwistWithCovariance", "-e", "-f0"]))
-        self.assertEqual('"{twist: {linear: {x: 0.0, y: 0.0, z: 0.0}, angular: {x: 0.0, y: 0.0, z: 0.0}}, covariance: [\n    0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,\n    0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,\n    0.0, 0.0, 0.0, 0.0]}"', rosmsg_cmd_prototype(["msg", "geometry_msgs/TwistWithCovariance", "-f1"]))
-        self.assertEqual('"twist:\n  linear: {x: 0.0, y: 0.0, z: 0.0}\n  angular: {x: 0.0, y: 0.0, z: 0.0}\ncovariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,\n  0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,\n  0.0, 0.0, 0.0, 0.0, 0.0, 0.0]"', rosmsg_cmd_prototype(["msg", "geometry_msgs/TwistWithCovariance"]))
-
-    def test_rosmsg_cmd_prototype_geom_msgs_Polygon(self):
-        self.assertEqual('"points:\n- x: 0.0\n  y: 0.0\n  z: 0.0"', rosmsg_cmd_prototype(["msg", "geometry_msgs/Polygon"]))
diff --git a/tools/rosnode/CHANGELOG.rst b/tools/rosnode/CHANGELOG.rst
index 49e588c..6194f1f 100644
--- a/tools/rosnode/CHANGELOG.rst
+++ b/tools/rosnode/CHANGELOG.rst
@@ -2,6 +2,9 @@
 Changelog for package rosnode
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.12.3 (2016-09-17)
+-------------------
+
 1.12.2 (2016-06-03)
 -------------------
 * add --quiet option (`#809 <https://github.com/ros/ros_comm/pull/809>`_)
diff --git a/tools/rosnode/package.xml b/tools/rosnode/package.xml
index f7a43ed..d1bea28 100644
--- a/tools/rosnode/package.xml
+++ b/tools/rosnode/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>rosnode</name>
-  <version>1.12.2</version>
+  <version>1.12.3</version>
   <description>
     rosnode is a command-line tool for displaying debug information
     about ROS <a href="http://www.ros.org/wiki/Nodes">Nodes</a>,
diff --git a/tools/rosout/CHANGELOG.rst b/tools/rosout/CHANGELOG.rst
index 79d4f8e..7360694 100644
--- a/tools/rosout/CHANGELOG.rst
+++ b/tools/rosout/CHANGELOG.rst
@@ -2,6 +2,9 @@
 Changelog for package rosout
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.12.3 (2016-09-17)
+-------------------
+
 1.12.2 (2016-06-03)
 -------------------
 
diff --git a/tools/rosout/package.xml b/tools/rosout/package.xml
index f6012e9..d8f1324 100644
--- a/tools/rosout/package.xml
+++ b/tools/rosout/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>rosout</name>
-  <version>1.12.2</version>
+  <version>1.12.3</version>
   <description>
      System-wide logging mechanism for messages sent to the /rosout topic.
   </description>
diff --git a/tools/rosparam/CHANGELOG.rst b/tools/rosparam/CHANGELOG.rst
index 4a67ee7..3ef6aab 100644
--- a/tools/rosparam/CHANGELOG.rst
+++ b/tools/rosparam/CHANGELOG.rst
@@ -2,6 +2,9 @@
 Changelog for package rosparam
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.12.3 (2016-09-17)
+-------------------
+
 1.12.2 (2016-06-03)
 -------------------
 
diff --git a/tools/rosparam/package.xml b/tools/rosparam/package.xml
index f4db8f6..7050dd5 100644
--- a/tools/rosparam/package.xml
+++ b/tools/rosparam/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>rosparam</name>
-  <version>1.12.2</version>
+  <version>1.12.3</version>
   <description>
     rosparam contains the rosparam command-line tool for getting and
     setting ROS Parameters on the <a
diff --git a/tools/rosservice/CHANGELOG.rst b/tools/rosservice/CHANGELOG.rst
index b353110..b011390 100644
--- a/tools/rosservice/CHANGELOG.rst
+++ b/tools/rosservice/CHANGELOG.rst
@@ -2,6 +2,10 @@
 Changelog for package rosservice
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.12.3 (2016-09-17)
+-------------------
+* fix rosservice call for Python 3 (`#847 <https://github.com/ros/ros_comm/pull/847>`_)
+
 1.12.2 (2016-06-03)
 -------------------
 
diff --git a/tools/rosservice/package.xml b/tools/rosservice/package.xml
index 8ddb967..9a770a2 100644
--- a/tools/rosservice/package.xml
+++ b/tools/rosservice/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>rosservice</name>
-  <version>1.12.2</version>
+  <version>1.12.3</version>
   <description>
     rosservice contains the rosservice command-line tool for listing
     and querying ROS <a
diff --git a/tools/rosservice/src/rosservice/__init__.py b/tools/rosservice/src/rosservice/__init__.py
index 6a7f88d..88fa01d 100644
--- a/tools/rosservice/src/rosservice/__init__.py
+++ b/tools/rosservice/src/rosservice/__init__.py
@@ -50,9 +50,9 @@ import sys
 import socket
 
 try:
-    from cStringIO import StringIO  # Python 2.x
+    from cStringIO import StringIO as BufferType  # Python 2.x
 except ImportError:
-    from io import StringIO  # Python 3.x
+    from io import BytesIO as BufferType  # Python 3.x
 
 import genpy
 
@@ -121,7 +121,7 @@ def get_service_headers(service_name, service_uri):
             header = { 'probe':'1', 'md5sum':'*',
                        'callerid':'/rosservice', 'service':service_name}
             rosgraph.network.write_ros_handshake_header(s, header)
-            return rosgraph.network.read_ros_handshake_header(s, StringIO(), 2048)
+            return rosgraph.network.read_ros_handshake_header(s, BufferType(), 2048)
         except socket.error:
             raise ROSServiceIOException("Unable to communicate with service [%s], address [%s]"%(service_name, service_uri))
     finally:
diff --git a/tools/rostest/CHANGELOG.rst b/tools/rostest/CHANGELOG.rst
index 4251a0f..55a7e70 100644
--- a/tools/rostest/CHANGELOG.rst
+++ b/tools/rostest/CHANGELOG.rst
@@ -2,6 +2,11 @@
 Changelog for package rostest
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.12.3 (2016-09-17)
+-------------------
+* add test node if topic message is published at least once (`#863 <https://github.com/ros/ros_comm/issues/863>`_)
+* add_rostest_gtest does now add the created gtest-target as a dependeny to the created rostest (`#830 <https://github.com/ros/ros_comm/pull/830>`_)
+
 1.12.2 (2016-06-03)
 -------------------
 
diff --git a/tools/rostest/CMakeLists.txt b/tools/rostest/CMakeLists.txt
index b7f08b1..13b473d 100644
--- a/tools/rostest/CMakeLists.txt
+++ b/tools/rostest/CMakeLists.txt
@@ -12,8 +12,9 @@ catkin_package(DEPENDS Boost
   )
 catkin_python_setup()
 
-catkin_install_python(PROGRAMS nodes/hztest
-  DESTINATION  ${CATKIN_PACKAGE_SHARE_DESTINATION}/nodes/hztest)
+catkin_install_python(
+  PROGRAMS nodes/hztest nodes/paramtest nodes/publishtest
+  DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/nodes)
 install(DIRECTORY include/${PROJECT_NAME}/
   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
   FILES_MATCHING PATTERN "*.h")
@@ -28,6 +29,8 @@ if(CATKIN_ENABLE_TESTING)
 
   add_rostest(test/hztest0.test)
   add_rostest(test/hztest.test)
+  add_rostest(test/publishtest.test)
   add_rostest(test/clean_master.test)
   add_rostest(test/distro_version.test)
+  add_rostest(test/param.test)
 endif()
diff --git a/tools/rostest/cmake/rostest-extras.cmake.em b/tools/rostest/cmake/rostest-extras.cmake.em
index 6c13124..324f3b5 100644
--- a/tools/rostest/cmake/rostest-extras.cmake.em
+++ b/tools/rostest/cmake/rostest-extras.cmake.em
@@ -83,7 +83,7 @@ function(add_rostest_gtest target launch_file)
     if(TARGET tests)
       add_dependencies(tests ${target})
     endif()
-    add_rostest(${launch_file})
+    add_rostest(${launch_file} DEPENDENCIES ${target})
   endif()
 endfunction()
 
diff --git a/tools/rostest/nodes/paramtest b/tools/rostest/nodes/paramtest
new file mode 100755
index 0000000..a26ff2c
--- /dev/null
+++ b/tools/rostest/nodes/paramtest
@@ -0,0 +1,110 @@
+#!/usr/bin/env python
+# Software License Agreement (BSD License)
+#
+# Copyright (c) 2008, Willow Garage, Inc.
+# All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+#  * Redistributions of source code must retain the above copyright
+#    notice, this list of conditions and the following disclaimer.
+#  * Redistributions in binary form must reproduce the above
+#    copyright notice, this list of conditions and the following
+#    disclaimer in the documentation and/or other materials provided
+#    with the distribution.
+#  * Neither the name of Willow Garage, Inc. nor the names of its
+#    contributors may be used to endorse or promote products derived
+#    from this software without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+
+# Original copied from hztest node
+# https://github.com/ros/ros_comm/blob/24e45419bdd4b0d588321e3b376650c7a51bf11c/tools/rostest/nodes/hztest
+# Integration test node that checks if a designated parameter is already
+# registered at the Parameter Server. Following parameters must be set:
+#
+#  * ~/param_name_target: expected parameter name
+#  * ~/test_duration: time (in secs) to run test
+#
+
+from __future__ import print_function
+
+import sys
+import threading
+import time
+import unittest
+
+import rospy
+import rostest
+
+CLASSNAME = 'paramtest'
+
+
+class ParamTest(unittest.TestCase):
+    def __init__(self, *args):
+        super(ParamTest, self).__init__(*args)
+        rospy.init_node(CLASSNAME)
+
+        self.lock = threading.Lock()
+        self.parameter_obtained = False
+
+    def setUp(self):
+        self.errors = []
+
+    def test_param(self):
+        # performs two tests of a node, first with /rostime off,
+        # then with /rostime on
+
+        # Fetch parameters
+        try:
+            # Getting the attributes of the test.
+            testattr_paramname_target = rospy.get_param("~param_name_target")
+            paramvalue_expected = rospy.get_param("~param_value_expected", None)  # This is the expected param value.
+            # length of test
+            testattr_duration = float(rospy.get_param("~test_duration", 5))
+            # time to wait before
+            wait_time = rospy.get_param("~wait_time", 20)
+        except KeyError as e:
+            self.fail("ParamTest not initialized properly. Parameter [%s] not set. Caller ID: [%s] Resolved name: [%s]"%(str(e), rospy.get_caller_id(), rospy.resolve_name(e.args[0])))
+        print("Parameter: %s Test Duration: %s" % (testattr_paramname_target, testattr_duration))
+        self._test_param(testattr_paramname_target, testattr_duration, wait_time, paramvalue_expected)
+
+    def _test_param(self, testattr_paramname_target, testattr_duration, wait_time, paramvalue_expected=None):
+        self.assert_(testattr_duration > 0.0, "bad parameter (test_duration)")
+        self.assert_(len(testattr_paramname_target), "bad parameter (testattr_paramname_target)")
+
+        print("Waiting for parameters")
+
+        wallclock_timeout_t = time.time() + wait_time
+        param_obtained = None
+        while not param_obtained and time.time() < wallclock_timeout_t:
+            try:
+                param_obtained = rospy.get_param(testattr_paramname_target)
+            except KeyError as e:
+                print('Designated parameter [%s] is not registered yet, will wait. Caller ID: [%s] Resolved name: [%s]'%(testattr_paramname_target, rospy.get_caller_id(), rospy.resolve_name(e.args[0])))
+            time.sleep(0.1)
+
+        if paramvalue_expected:
+            self.assertEqual(paramvalue_expected, param_obtained)
+        else:
+            self.assertIsNotNone(param_obtained)
+
+if __name__ == '__main__':
+    try:
+        rostest.run('rostest', CLASSNAME, ParamTest, sys.argv)
+    except KeyboardInterrupt:
+        pass
+    print("{} exiting".format(CLASSNAME))
diff --git a/tools/rostest/nodes/publishtest b/tools/rostest/nodes/publishtest
new file mode 100755
index 0000000..b298491
--- /dev/null
+++ b/tools/rostest/nodes/publishtest
@@ -0,0 +1,149 @@
+#!/usr/bin/env python
+###############################################################################
+# Software License Agreement (BSD License)
+#
+# Copyright (c) 2016, Kentaro Wada.
+# All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+#  * Redistributions of source code must retain the above copyright
+#    notice, this list of conditions and the following disclaimer.
+#  * Redistributions in binary form must reproduce the above
+#    copyright notice, this list of conditions and the following
+#    disclaimer in the documentation and/or other materials provided
+#    with the distribution.
+#  * Neither the name of Willow Garage, Inc. nor the names of its
+#    contributors may be used to endorse or promote products derived
+#    from this software without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+###############################################################################
+
+"""
+Integration test node that subscribes to any topic and verifies
+there is at least one message publishing of the topic.
+below parameters must be set:
+
+<test name="publishtest"
+      test-name="publishtest"
+      pkg="rostest" type="publishtest">
+  <rosparam>
+    topics:
+      - name: a topic name
+        timeout: timeout for the topic
+      - name: another topic name
+        timeout: timeout for the topic
+  </rosparam>
+</test>
+
+Author: Kentaro Wada <www.kentaro.wada at gmail.com>
+"""
+
+import sys
+import unittest
+
+from nose.tools import assert_true
+
+import rospy
+import rostopic
+
+
+PKG = 'rostest'
+NAME = 'publishtest'
+
+
+class PublishChecker(object):
+    def __init__(self, topic_name, timeout, negative):
+        self.topic_name = topic_name
+        self.negative = negative
+        self.deadline = rospy.Time.now() + rospy.Duration(timeout)
+        msg_class, _, _ = rostopic.get_topic_class(
+            rospy.resolve_name(topic_name), blocking=True)
+        self.msg = None
+        self.sub = rospy.Subscriber(topic_name, msg_class, self._callback)
+
+    def _callback(self, msg):
+        self.msg = msg
+
+    def assert_published(self):
+        if self.msg:
+            return not self.negative
+        if rospy.Time.now() > self.deadline:
+            return self.negative
+        return None
+
+
+class PublishTest(unittest.TestCase):
+    def __init__(self, *args):
+        super(self.__class__, self).__init__(*args)
+        rospy.init_node(NAME)
+        # scrape rosparam
+        self.topics = []
+        params = rospy.get_param('~topics', [])
+        for param in params:
+            if 'name' not in param:
+                self.fail("'name' field in rosparam is required but not specified.")
+            topic = {'timeout': 10, 'negative': False}
+            topic.update(param)
+            self.topics.append(topic)
+        # check if there is at least one topic
+        if not self.topics:
+            self.fail('No topic is specified in rosparam.')
+
+    def test_publish(self):
+        """Test topics are published and messages come"""
+        use_sim_time = rospy.get_param('/use_sim_time', False)
+        while use_sim_time and (rospy.Time.now() == rospy.Time(0)):
+            rospy.logwarn('/use_sim_time is specified and rostime is 0, '
+                          '/clock is published?')
+            rospy.sleep(0.1)
+        # subscribe topics
+        checkers = []
+        for topic in self.topics:
+            topic_name = topic['name']
+            timeout = topic['timeout']
+            negative = topic['negative']
+            print('Waiting [%s] for [%d] seconds with negative [%s]'
+                  % (topic_name, timeout, negative))
+            checkers.append(
+                PublishChecker(topic_name, timeout, negative))
+        deadline = max(checker.deadline for checker in checkers)
+        # assert
+        finished_topics = []
+        while not rospy.is_shutdown():
+            if len(self.topics) == len(finished_topics):
+                break
+            for checker in checkers:
+                if checker.topic_name in finished_topics:
+                    continue  # skip topic testing has finished
+                ret = checker.assert_published()
+                if ret is None:
+                    continue  # skip if there is no test result
+                finished_topics.append(checker.topic_name)
+                if checker.negative:
+                    assert_true(
+                        ret, 'Topic [%s] is published' % (checker.topic_name))
+                else:
+                    assert_true(
+                        ret,
+                        'Topic [%s] is not published' % (checker.topic_name))
+            rospy.sleep(0.01)
+
+
+if __name__ == '__main__':
+    import rostest
+    rostest.run(PKG, NAME, PublishTest, sys.argv)
diff --git a/tools/rostest/package.xml b/tools/rostest/package.xml
index 3ae0076..8a19462 100644
--- a/tools/rostest/package.xml
+++ b/tools/rostest/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>rostest</name>
-  <version>1.12.2</version>
+  <version>1.12.3</version>
   <description>
      Integration test suite based on roslaunch that is compatible with xUnit frameworks.
   </description>
diff --git a/tools/rostest/test/hztest.test b/tools/rostest/test/hztest.test
index b610676..23de375 100644
--- a/tools/rostest/test/hztest.test
+++ b/tools/rostest/test/hztest.test
@@ -8,4 +8,17 @@
   <param name="hztest1/wait_time" value="21.0" />    
   <test test-name="hztest_test" pkg="rostest" type="hztest" name="hztest1" />
 
+  <!-- Below also works:
+
+  <test test-name="hztest_test" pkg="rostest" type="hztest" name="hztest1">
+    <rosparam>
+      topic: chatter
+      hz: 10.0
+      hzerror: 0.5
+      test_duration: 5.0
+      wait_time: 21.0
+    </rosparam>
+  </test>
+
+  -->
 </launch>
diff --git a/clients/rospy/test_nodes/talker.py b/tools/rostest/test/just_advertise
similarity index 73%
copy from clients/rospy/test_nodes/talker.py
copy to tools/rostest/test/just_advertise
index ed67fed..4850703 100755
--- a/clients/rospy/test_nodes/talker.py
+++ b/tools/rostest/test/just_advertise
@@ -1,7 +1,8 @@
 #!/usr/bin/env python
+###############################################################################
 # Software License Agreement (BSD License)
 #
-# Copyright (c) 2008, Willow Garage, Inc.
+# Copyright (c) 2016, Kentaro Wada.
 # All rights reserved.
 #
 # Redistribution and use in source and binary forms, with or without
@@ -30,24 +31,21 @@
 # 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.
+###############################################################################
 
-## Simple talker demo that published std_msgs/Strings messages
-## to the 'chatter' topic
+"""
+This node is designed for testing and just advertises a topic for the specified message class.
+
+Author: Kentaro Wada <www.kentaro.wada at gmail.com>
+"""
 
 import rospy
-from std_msgs.msg import String
+import roslib.message
+
 
-def talker():
-    pub = rospy.Publisher('chatter', String, queue_size=10)
-    rospy.init_node('talker', anonymous=True)
-    r = rospy.Rate(10) # 10hz
-    while not rospy.is_shutdown():
-        str = "hello world %s"%rospy.get_time()
-        rospy.loginfo(str)
-        pub.publish(str)
-        r.sleep()
-        
 if __name__ == '__main__':
-    try:
-        talker()
-    except rospy.ROSInterruptException: pass
+    rospy.init_node('just_advertise')
+    msg_name = rospy.get_param('~msg_name')
+    msg_class = roslib.message.get_message_class(msg_name)
+    pub = rospy.Publisher('~output', msg_class, queue_size=1)
+    rospy.spin()
diff --git a/tools/rostest/test/param.test b/tools/rostest/test/param.test
new file mode 100644
index 0000000..3359f3b
--- /dev/null
+++ b/tools/rostest/test/param.test
@@ -0,0 +1,30 @@
+<launch>
+  <!-- These parameters are registered to Parameter Server and
+       will be accessed by the test cases. -->
+  <param name="param_nonempty" value="This param is not empty." />
+  <param name="param_empty" value="" />
+  <param name="param_value_specific" value="Opensource Robotics is forever." />
+
+  <test pkg="rostest" type="paramtest" name="paramtest_nonempty"
+        test-name="paramtest_nonempty">
+    <param name="param_name_target" value="param_nonempty" />
+    <param name="test_duration" value="5.0" />
+    <param name="wait_time" value="20.0" />
+  </test>
+
+  <test pkg="rostest" type="paramtest" name="paramtest_empty"
+        test-name="paramtest_empty">
+    <param name="param_name_target" value="param_empty" />
+    <param name="test_duration" value="5.0" />
+    <param name="wait_time" value="30.0" />
+  </test>
+
+  <test pkg="rostest" type="paramtest" name="paramtest_value_specific_correct"
+        test-name="paramtest_value_specific_correct">
+    <param name="param_name_target" value="param_value_specific" />
+    <param name="param_value_expected" value="Opensource Robotics is forever." />
+    <param name="test_duration" value="5.0" />
+    <param name="wait_time" value="30.0" />
+  </test>
+
+</launch>
diff --git a/tools/rostest/test/publishtest.test b/tools/rostest/test/publishtest.test
new file mode 100644
index 0000000..76ffc15
--- /dev/null
+++ b/tools/rostest/test/publishtest.test
@@ -0,0 +1,35 @@
+<launch>
+
+  <node name="talker_0"
+        pkg="rospy" type="talker.py">
+    <remap from="chatter" to="~output" />
+  </node>
+
+  <node name="talker_1"
+        pkg="rospy" type="talker.py">
+    <remap from="chatter" to="~output" />
+  </node>
+
+  <node name="talker_2"
+        pkg="rostest" type="just_advertise">
+    <rosparam>
+      msg_name: std_msgs/String
+    </rosparam>
+  </node>
+
+  <test name="publishtest"
+        test-name="publishtest"
+        pkg="rostest" type="publishtest">
+    <rosparam>
+      topics:
+        - name: talker_0/output
+          timeout: 10
+          negative: False
+        - name: talker_1/output
+        - name: talker_2/output
+          timeout: 3
+          negative: True
+    </rosparam>
+  </test>
+
+</launch>
diff --git a/tools/rostopic/CHANGELOG.rst b/tools/rostopic/CHANGELOG.rst
index 3a14465..5de0e21 100644
--- a/tools/rostopic/CHANGELOG.rst
+++ b/tools/rostopic/CHANGELOG.rst
@@ -2,6 +2,13 @@
 Changelog for package rostopic
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.12.3 (2016-09-17)
+-------------------
+* show topic field type with rostopic type (`#860 <https://github.com/ros/ros_comm/issues/860>`_)
+* show stat for rostopic echo --noarr/nostr (`#724 <https://github.com/ros/ros_comm/pull/724>`_, `#872 <https://github.com/ros/ros_comm/pull/872>`_)
+* add support for multiple topics in rostopic hz (`#712 <https://github.com/ros/ros_comm/pull/712>`_, `#886 <https://github.com/ros/ros_comm/pull/886>`_, `#888 <https://github.com/ros/ros_comm/pull/888>`_)
+* more detailed help string for rostopic echo -p (`#816 <https://github.com/ros/ros_comm/issues/816>`_)
+
 1.12.2 (2016-06-03)
 -------------------
 
diff --git a/tools/rostopic/package.xml b/tools/rostopic/package.xml
index 4c8c385..45cc923 100644
--- a/tools/rostopic/package.xml
+++ b/tools/rostopic/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>rostopic</name>
-  <version>1.12.2</version>
+  <version>1.12.3</version>
   <description>
     rostopic contains the rostopic command-line tool for displaying
     debug information about
diff --git a/tools/rostopic/src/rostopic/__init__.py b/tools/rostopic/src/rostopic/__init__.py
index fe32914..d956518 100644
--- a/tools/rostopic/src/rostopic/__init__.py
+++ b/tools/rostopic/src/rostopic/__init__.py
@@ -38,6 +38,7 @@ from __future__ import division, print_function
 
 NAME='rostopic'
 
+import argparse
 import os
 import sys
 import math
@@ -99,11 +100,16 @@ class ROSTopicHz(object):
     """
     def __init__(self, window_size, filter_expr=None, use_wtime=False):
         import threading
+        from collections import defaultdict
         self.lock = threading.Lock()
         self.last_printed_tn = 0
-        self.msg_t0 = -1.
+        self.msg_t0 = -1
         self.msg_tn = 0
-        self.times =[]
+        self.times = []
+        self._last_printed_tn = defaultdict(int)
+        self._msg_t0 = defaultdict(lambda: -1)
+        self._msg_tn = defaultdict(int)
+        self._times = defaultdict(list)
         self.filter_expr = filter_expr
         self.use_wtime = use_wtime
         
@@ -111,11 +117,52 @@ class ROSTopicHz(object):
         if window_size < 0:
             window_size = 50000
         self.window_size = window_size
-                
-    def callback_hz(self, m):
+
+    def get_last_printed_tn(self, topic=None):
+        if topic is None:
+            return self.last_printed_tn
+        return self._last_printed_tn[topic]
+
+    def set_last_printed_tn(self, value, topic=None):
+        if topic is None:
+            self.last_printed_tn = value
+        self._last_printed_tn[topic] = value
+
+    def get_msg_t0(self, topic=None):
+        if topic is None:
+            return self.msg_t0
+        return self._msg_t0[topic]
+
+    def set_msg_t0(self, value, topic=None):
+        if topic is None:
+            self.msg_t0 = value
+        self._msg_t0[topic] = value
+
+    def get_msg_tn(self, topic=None):
+        if topic is None:
+            return self.msg_tn
+        return self._msg_tn[topic]
+
+    def set_msg_tn(self, value, topic=None):
+        if topic is None:
+            self.msg_tn = value
+        self._msg_tn[topic] = value
+
+    def get_times(self, topic=None):
+        if topic is None:
+            return self.times
+        return self._times[topic]
+
+    def set_times(self, value, topic=None):
+        if topic is None:
+            self.times = value
+        self._times[topic] = value
+
+    def callback_hz(self, m, topic=None):
         """
         ros sub callback
         :param m: Message instance
+        :param topic: Topic name
         """
         # #694: ignore messages that don't match filter
         if self.filter_expr is not None and not self.filter_expr(m):
@@ -126,33 +173,36 @@ class ROSTopicHz(object):
 
             # time reset
             if curr_rostime.is_zero():
-                if len(self.times) > 0:
+                if len(self.get_times(topic=topic)) > 0:
                     print("time has reset, resetting counters")
-                    self.times = []
+                    self.set_times([], topic=topic)
                 return
             
             curr = curr_rostime.to_sec() if not self.use_wtime else \
                     rospy.Time.from_sec(time.time()).to_sec()
-            if self.msg_t0 < 0 or self.msg_t0 > curr:
-                self.msg_t0 = curr
-                self.msg_tn = curr
-                self.times = []
+            if self.get_msg_t0(topic=topic) < 0 or self.get_msg_t0(topic=topic) > curr:
+                self.set_msg_t0(curr, topic=topic)
+                self.set_msg_tn(curr, topic=topic)
+                self.set_times([], topic=topic)
             else:
-                self.times.append(curr - self.msg_tn)
-                self.msg_tn = curr
+                self.get_times(topic=topic).append(curr - self.get_msg_tn(topic=topic))
+                self.set_msg_tn(curr, topic=topic)
 
             #only keep statistics for the last 10000 messages so as not to run out of memory
-            if len(self.times) > self.window_size - 1:
-                self.times.pop(0)
+            if len(self.get_times(topic=topic)) > self.window_size - 1:
+                self.get_times(topic=topic).pop(0)
 
-    def print_hz(self):
+    def get_hz(self, topic=None):
         """
-        print the average publishing rate to screen
+        calculate the average publising rate
+
+        @returns: tuple of stat results
+            (rate, min_delta, max_delta, standard deviation, window number)
+            None when waiting for the first message or there is no new one
         """
-        if not self.times:
+        if not self.get_times(topic=topic):
             return
-        elif self.msg_tn == self.last_printed_tn:
-            print("no new messages")
+        elif self.get_msg_tn(topic=topic) == self.get_last_printed_tn(topic=topic):
             return
         with self.lock:
             #frequency
@@ -164,53 +214,106 @@ class ROSTopicHz(object):
             # makes it easier for users to see when a publisher dies,
             # so the decay is no longer necessary.
             
-            n = len(self.times)
+            n = len(self.get_times(topic=topic))
             #rate = (n - 1) / (rospy.get_time() - self.msg_t0)
-            mean = sum(self.times) / n
+            mean = sum(self.get_times(topic=topic)) / n
             rate = 1./mean if mean > 0. else 0
 
             #std dev
-            std_dev = math.sqrt(sum((x - mean)**2 for x in self.times) /n)
+            std_dev = math.sqrt(sum((x - mean)**2 for x in self.get_times(topic=topic)) /n)
 
             # min and max
-            max_delta = max(self.times)
-            min_delta = min(self.times)
+            max_delta = max(self.get_times(topic=topic))
+            min_delta = min(self.get_times(topic=topic))
+
+            self.set_last_printed_tn(self.get_msg_tn(topic=topic), topic=topic)
 
-            self.last_printed_tn = self.msg_tn
-        print("average rate: %.3f\n\tmin: %.3fs max: %.3fs std dev: %.5fs window: %s"%(rate, min_delta, max_delta, std_dev, n+1))
+        return rate, min_delta, max_delta, std_dev, n+1
+
+    def print_hz(self, topics=(None,)):
+        """
+        print the average publishing rate to screen
+        """
+        if len(topics) == 1:
+            ret = self.get_hz(topics[0])
+            if ret is None:
+                print("no new messages")
+                return
+            rate, min_delta, max_delta, std_dev, window = ret
+            print("average rate: %.3f\n\tmin: %.3fs max: %.3fs std dev: %.5fs window: %s"%(rate, min_delta, max_delta, std_dev, window))
+            return
+
+        # monitoring multiple topics' hz
+        header = ['topic', 'rate', 'min_delta', 'max_delta', 'std_dev', 'window']
+        stats = {h: [] for h in header}
+        for topic in topics:
+            hz_stat = self.get_hz(topic)
+            if hz_stat is None:
+                continue
+            rate, min_delta, max_delta, std_dev, window = hz_stat
+            stats['window'].append(str(window))
+            stats['topic'].append(topic)
+            stats['rate'].append('{:.4}'.format(rate))
+            stats['min_delta'].append('{:.4}'.format(min_delta))
+            stats['max_delta'].append('{:.4}'.format(max_delta))
+            stats['std_dev'].append('{:.4}'.format(std_dev))
+            stats['window'].append(str(window))
+        if not stats['topic']:
+            print('no new messages')
+            return
+        print(_get_ascii_table(header, stats))
+
+def _get_ascii_table(header, cols):
+    # compose table with left alignment
+    header_aligned = []
+    col_widths = []
+    for h in header:
+        col_width = max(len(h), max(len(el) for el in cols[h]))
+        col_widths.append(col_width)
+        header_aligned.append(h.center(col_width))
+        for i, el in enumerate(cols[h]):
+            cols[h][i] = str(cols[h][i]).ljust(col_width)
+    # sum of col and each 3 spaces width
+    table_width = sum(col_widths) + 3 * (len(header) - 1)
+    n_rows = len(cols[header[0]])
+    body = '\n'.join('   '.join(cols[h][i] for h in header) for i in xrange(n_rows))
+    table = '{header}\n{hline}\n{body}\n'.format(
+        header='   '.join(header_aligned), hline='=' * table_width, body=body)
+    return table
 
 def _sleep(duration):
     rospy.rostime.wallsleep(duration)
 
-def _rostopic_hz(topic, window_size=-1, filter_expr=None, use_wtime=False):
+def _rostopic_hz(topics, window_size=-1, filter_expr=None, use_wtime=False):
     """
     Periodically print the publishing rate of a topic to console until
     shutdown
-    :param topic: topic name, ``str``
+    :param topics: topic names, ``list`` of ``str``
     :param window_size: number of messages to average over, -1 for infinite, ``int``
     :param filter_expr: Python filter expression that is called with m, the message instance
     """
-    msg_class, real_topic, _ = get_topic_class(topic, blocking=True) #pause hz until topic is published
+    _check_master()
     if rospy.is_shutdown():
         return
     rospy.init_node(NAME, anonymous=True)
     rt = ROSTopicHz(window_size, filter_expr=filter_expr, use_wtime=use_wtime)
-    # we use a large buffer size as we don't know what sort of messages we're dealing with.
-    # may parameterize this in the future
-    if filter_expr is not None:
-        # have to subscribe with topic_type
-        sub = rospy.Subscriber(real_topic, msg_class, rt.callback_hz)
-    else:
-        sub = rospy.Subscriber(real_topic, rospy.AnyMsg, rt.callback_hz)        
-    print("subscribed to [%s]"%real_topic)
+    for topic in topics:
+        msg_class, real_topic, _ = get_topic_class(topic, blocking=True) # pause hz until topic is published
+        # we use a large buffer size as we don't know what sort of messages we're dealing with.
+        # may parameterize this in the future
+        if filter_expr is not None:
+            # have to subscribe with topic_type
+            rospy.Subscriber(real_topic, msg_class, rt.callback_hz, callback_args=topic)
+        else:
+            rospy.Subscriber(real_topic, rospy.AnyMsg, rt.callback_hz, callback_args=topic)
+        print("subscribed to [%s]" % real_topic)
 
     if rospy.get_param('use_sim_time', False):
         print("WARNING: may be using simulated time",file=sys.stderr)
 
     while not rospy.is_shutdown():
         _sleep(1.0)
-        rt.print_hz()
-
+        rt.print_hz(topics)
 
 class ROSTopicDelay(object):
 
@@ -619,14 +722,15 @@ def _sub_str_plot_fields(val, f, field_filter):
     return None
 
 
-def _str_plot(val, time_offset=None, current_time=None, field_filter=None, type_information=None, fixed_numeric_width=None):
+def _str_plot(val, time_offset=None, current_time=None, field_filter=None, type_information=None, fixed_numeric_width=None, value_transform_fn=None):
     """
     Convert value to matlab/octave-friendly CSV string representation.
 
     :param val: message
     :param current_time: current :class:`genpy.Time` to use if message does not contain its own timestamp.
     :param time_offset: (optional) for time printed for message, print as offset against this :class:`genpy.Time`
-    :param field_filter: filter the fields that are strified for Messages, ``fn(Message)->iter(str)``
+    :param field_filter: filter the fields that are stringified for Messages, ``fn(Message)->iter(str)``
+    :param value_transform_fn: Not used but for same API as CallbackEcho.custom_strify_message
     :returns: comma-separated list of field values in val, ``str``
     """
         
@@ -711,15 +815,17 @@ class CallbackEcho(object):
     def __init__(self, topic, msg_eval, plot=False, filter_fn=None,
                  echo_clear=False, echo_all_topics=False,
                  offset_time=False, count=None,
-                 field_filter_fn=None, fixed_numeric_width=None):
+                 field_filter_fn=None, fixed_numeric_width=None,
+                 value_transform_fn=None):
         """
-        :param plot: if ``True``, echo in plotting-friendly format, ``bool``
+        :param plot: if ``True``, echo in plotting-friendly format (csv), ``bool``
         :param filter_fn: function that evaluates to ``True`` if message is to be echo'd, ``fn(topic, msg)``
         :param echo_all_topics: (optional) if ``True``, echo all messages in bag, ``bool``
         :param offset_time: (optional) if ``True``, display time as offset from current time, ``bool``
         :param count: number of messages to echo, ``None`` for infinite, ``int``
-        :param field_filter_fn: filter the fields that are strified for Messages, ``fn(Message)->iter(str)``
+        :param field_filter_fn: filter the fields that are stringified for Messages, ``fn(Message)->iter(str)``
         :param fixed_numeric_width: fixed width for numeric values, ``None`` for automatic, ``int``
+        :param value_transform_fn: transform the values of Messages, ``fn(Message)->Message``
         """
         if topic and topic[-1] == '/':
             topic = topic[:-1]
@@ -752,6 +858,7 @@ class CallbackEcho(object):
                 self.prefix = '\033[2J\033[;H'
 
         self.field_filter=field_filter_fn
+        self.value_transform=value_transform_fn
         
         # first tracks whether or not we've printed anything yet. Need this for printing plot fields.
         self.first = True
@@ -760,10 +867,13 @@ class CallbackEcho(object):
         self.last_topic = None
         self.last_msg_eval = None
 
-    def custom_strify_message(self, val, indent='', time_offset=None, current_time=None, field_filter=None, type_information=None, fixed_numeric_width=None):
+    def custom_strify_message(self, val, indent='', time_offset=None, current_time=None, field_filter=None,
+                              type_information=None, fixed_numeric_width=None, value_transform=None):
         # ensure to print uint8[] as array of numbers instead of string
         if type_information and type_information.startswith('uint8['):
             val = [ord(x) for x in val]
+        if value_transform is not None:
+            val = value_transform(val)
         return genpy.message.strify_message(val, indent=indent, time_offset=time_offset, current_time=current_time, field_filter=field_filter, fixed_numeric_width=fixed_numeric_width)
 
     def callback(self, data, callback_args, current_time=None):
@@ -817,12 +927,16 @@ class CallbackEcho(object):
                 if self.offset_time:
                     sys.stdout.write(self.prefix+\
                                      self.str_fn(data, time_offset=rospy.get_rostime(),
-                                                 current_time=current_time, field_filter=self.field_filter, type_information=type_information, fixed_numeric_width=self.fixed_numeric_width) + \
+                                                 current_time=current_time, field_filter=self.field_filter,
+                                                 type_information=type_information, fixed_numeric_width=self.fixed_numeric_width,
+                                                 value_transform=self.value_transform) + \
                                      self.suffix + '\n')
                 else:
                     sys.stdout.write(self.prefix+\
                                      self.str_fn(data,
-                                                 current_time=current_time, field_filter=self.field_filter, type_information=type_information, fixed_numeric_width=self.fixed_numeric_width) + \
+                                                 current_time=current_time, field_filter=self.field_filter,
+                                                 type_information=type_information, fixed_numeric_width=self.fixed_numeric_width,
+                                                 value_transform=self.value_transform) + \
                                      self.suffix + '\n')
 
                 # we have to flush in order before piping to work
@@ -843,12 +957,19 @@ def _rostopic_type(topic):
     Print ROS message type of topic to screen
     :param topic: topic name, ``str``
     """
-    t, _, _ = get_topic_type(topic, blocking=False)
-    if t:
-        print(t)
-    else:
+    topic_type, topic_real_name, _ = get_topic_type(topic, blocking=False)
+    if topic_type is None:
         sys.stderr.write('unknown topic type [%s]\n'%topic)
         sys.exit(1)
+    elif topic == topic_real_name:
+        print(topic_type)
+    else:
+        field = topic[len(topic_real_name)+1:]
+        field_type = topic_type
+        for current_field in field.split('/'):
+            msg_class = roslib.message.get_message_class(field_type)
+            field_type = msg_class._slot_types[msg_class.__slots__.index(current_field)]
+        print('%s %s %s'%(topic_type, field, field_type))
 
 def _rostopic_echo_bag(callback_echo, bag_file):
     """
@@ -1247,17 +1368,59 @@ def _rostopic_cmd_echo(argv):
     except ValueError:
         parser.error("NUM_WIDTH must be an integer")
 
-    field_filter_fn = create_field_filter(options.nostr, options.noarr)
+    if options.plot:
+        field_filter_fn = create_field_filter(options.nostr, options.noarr)
+        value_transform_fn = None
+    else:
+        field_filter_fn = None
+        value_transform_fn = create_value_transform(options.nostr, options.noarr)
+
     callback_echo = CallbackEcho(topic, None, plot=options.plot,
                                  filter_fn=filter_fn,
                                  echo_clear=options.clear, echo_all_topics=options.all_topics,
                                  offset_time=options.offset_time, count=msg_count,
-                                 field_filter_fn=field_filter_fn, fixed_numeric_width=fixed_numeric_width)
+                                 field_filter_fn=field_filter_fn,
+                                 value_transform_fn=value_transform_fn,
+                                 fixed_numeric_width=fixed_numeric_width)
     try:
         _rostopic_echo(topic, callback_echo, bag_file=options.bag)
     except socket.error:
         sys.stderr.write("Network communication failed. Most likely failed to communicate with master.\n")
 
+def create_value_transform(echo_nostr, echo_noarr):
+    def value_transform(val):
+
+        class TransformedMessage(genpy.Message):
+            # These should be copy because changing these variables
+            # in transforming is problematic without its untransforming.
+            __slots__ = val.__slots__[:]
+            _slot_types = val._slot_types[:]
+
+        val_trans = TransformedMessage()
+
+        fields = val.__slots__
+        field_types = val._slot_types
+        for index, (f, t) in enumerate(zip(fields, field_types)):
+            f_val = getattr(val, f)
+            if echo_noarr and '[' in t:
+                setattr(val_trans, f, '<array type: %s, length: %s>' %
+                                      (t.rstrip('[]'), len(f_val)))
+                val_trans._slot_types[index] = 'string'
+            elif echo_nostr and 'string' in t:
+                setattr(val_trans, f, '<string length: %s>' % len(f_val))
+            else:
+                try:
+                    msg_class = genpy.message.get_message_class(t)
+                    if msg_class is None:
+                        # happens for list of ROS messages like std_msgs/String[]
+                        raise ValueError
+                    nested_transformed = value_transform(f_val)
+                    setattr(val_trans, f, nested_transformed)
+                except ValueError:
+                    setattr(val_trans, f, f_val)
+        return val_trans
+    return value_transform
+
 def create_field_filter(echo_nostr, echo_noarr):
     def field_filter(val):
         fields = val.__slots__
@@ -1282,12 +1445,15 @@ def _optparse_topic_only(cmd, argv):
     return rosgraph.names.script_resolve_name('rostopic', args[0])
 
 def _rostopic_cmd_type(argv):
-    _rostopic_type(_optparse_topic_only('type', argv))
-    
+    parser = argparse.ArgumentParser(prog='%s type' % NAME)
+    parser.add_argument('topic_or_field', help='Topic or field name')
+    args = parser.parse_args(argv[2:])
+    _rostopic_type(rosgraph.names.script_resolve_name('rostopic', args.topic_or_field))
+
 def _rostopic_cmd_hz(argv):
     args = argv[2:]
     from optparse import OptionParser
-    parser = OptionParser(usage="usage: %prog hz /topic", prog=NAME)
+    parser = OptionParser(usage="usage: %prog hz [options] /topic_0 [/topic_1 [topic_2 [..]]]", prog=NAME)
     parser.add_option("-w", "--window",
                       dest="window_size", default=-1,
                       help="window size, in # of messages, for calculating rate", metavar="WINDOW")
@@ -1301,8 +1467,6 @@ def _rostopic_cmd_hz(argv):
     (options, args) = parser.parse_args(args)
     if len(args) == 0:
         parser.error("topic must be specified")        
-    if len(args) > 1:
-        parser.error("you may only specify one input topic")
     try:
         if options.window_size != -1:
             import string
@@ -1311,7 +1475,8 @@ def _rostopic_cmd_hz(argv):
             window_size = options.window_size
     except:
         parser.error("window size must be an integer")
-    topic = rosgraph.names.script_resolve_name('rostopic', args[0])
+
+    topics = [rosgraph.names.script_resolve_name('rostopic', t) for t in args]
 
     # #694
     if options.filter_expr:
@@ -1322,7 +1487,7 @@ def _rostopic_cmd_hz(argv):
         filter_expr = expr_eval(options.filter_expr)
     else:
         filter_expr = None
-    _rostopic_hz(topic, window_size=window_size, filter_expr=filter_expr,
+    _rostopic_hz(topics, window_size=window_size, filter_expr=filter_expr,
                  use_wtime=options.use_wtime)
 
 
@@ -1894,7 +2059,7 @@ Commands:
 \trostopic info\tprint information about active topic
 \trostopic list\tlist active topics
 \trostopic pub\tpublish data to topic
-\trostopic type\tprint topic type
+\trostopic type\tprint topic or field type
 
 Type rostopic <command> -h for more detailed usage, e.g. 'rostopic echo -h'
 """)
diff --git a/tools/rostopic/test/check_rostopic_command_line_online.py b/tools/rostopic/test/check_rostopic_command_line_online.py
index 51c6d31..864965c 100755
--- a/tools/rostopic/test/check_rostopic_command_line_online.py
+++ b/tools/rostopic/test/check_rostopic_command_line_online.py
@@ -91,6 +91,10 @@ class TestRostopicOnline(unittest.TestCase):
             output = Popen([cmd, 'type', name], stdout=PIPE).communicate()[0]
             output = output.decode()
             self.assertEquals('std_msgs/String', output.strip())
+            # check type of topic field
+            output = Popen([cmd, 'type', name + '/data'], stdout=PIPE).communicate()[0]
+            output = output.decode()
+            self.assertEquals('std_msgs/String data string', output.strip())
 
             # find
             output = Popen([cmd, 'find', 'std_msgs/String'], stdout=PIPE).communicate()[0]
diff --git a/tools/rostopic/test/test_rostopic.py b/tools/rostopic/test/test_rostopic.py
index f8f9fdb..388bedd 100644
--- a/tools/rostopic/test/test_rostopic.py
+++ b/tools/rostopic/test/test_rostopic.py
@@ -131,6 +131,10 @@ class TestRostopic(unittest.TestCase):
                 rostopic.rostopicmain([cmd, 'type', s])
                 v = b.getvalue().strip()
                 self.assertEquals('std_msgs/String', v)
+                # check type of topic field
+                rostopic.rostopicmain([cmd, 'type', s + '/data'])
+                v = b.getvalue().strip()
+                self.assertEquals('std_msgs/String data string', v)
 
     def test_main(self):
         import rostopic
diff --git a/tools/topic_tools/CHANGELOG.rst b/tools/topic_tools/CHANGELOG.rst
index dee5c32..38d9bad 100644
--- a/tools/topic_tools/CHANGELOG.rst
+++ b/tools/topic_tools/CHANGELOG.rst
@@ -2,6 +2,10 @@
 Changelog for package topic_tools
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.12.3 (2016-09-17)
+-------------------
+* add abstract class to implement connection based transport (`#713 <https://github.com/ros/ros_comm/pull/713>`_)
+
 1.12.2 (2016-06-03)
 -------------------
 
diff --git a/tools/topic_tools/CMakeLists.txt b/tools/topic_tools/CMakeLists.txt
index bea81dd..ef0bed8 100644
--- a/tools/topic_tools/CMakeLists.txt
+++ b/tools/topic_tools/CMakeLists.txt
@@ -6,6 +6,7 @@ if(NOT WIN32)
 endif()
 
 find_package(catkin COMPONENTS cpp_common message_generation rosconsole roscpp rostime std_msgs xmlrpcpp)
+catkin_python_setup()
 
 include_directories(include)
 include_directories(${catkin_INCLUDE_DIRS})
@@ -100,6 +101,7 @@ if(CATKIN_ENABLE_TESTING)
   add_rostest(test/throttle_simtime.test)
   add_rostest(test/drop.test)
   add_rostest(test/relay.test)
+  add_rostest(test/lazy_transport.test)
   ## Latched test disabled until underlying issue in roscpp is resolved,
   ## #3385, #3434.
   #rosbuild_add_rostest(test/relay_latched.test)
diff --git a/tools/topic_tools/package.xml b/tools/topic_tools/package.xml
index f660dd4..c1bb9be 100644
--- a/tools/topic_tools/package.xml
+++ b/tools/topic_tools/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>topic_tools</name>
-  <version>1.12.2</version>
+  <version>1.12.3</version>
   <description>
     Tools for directing, throttling, selecting, and otherwise messing with
     ROS topics at a meta level. None of the programs in this package actually
diff --git a/tools/topic_tools/python/topic_tools/__init__.py b/tools/topic_tools/python/topic_tools/__init__.py
new file mode 100644
index 0000000..732ee5a
--- /dev/null
+++ b/tools/topic_tools/python/topic_tools/__init__.py
@@ -0,0 +1,79 @@
+import rospy
+
+
+__all__ = ('LazyTransport',)
+
+
+# define a new metaclass which overrides the '__call__' function
+# See: http://martyalchin.com/2008/jan/10/simple-plugin-framework/
+class MetaLazyTransport(type):
+
+    def __call__(cls, *args, **kwargs):
+        """Called when you call LazyTransport()"""
+        obj = type.__call__(cls, *args, **kwargs)
+        obj._post_init()
+        return obj
+
+
+class LazyTransport(rospy.SubscribeListener):
+    __metaclass__ = MetaLazyTransport
+
+    def __init__(self):
+        super(LazyTransport, self).__init__()
+        self._publishers = []
+        # self._connection_status has 3 meanings
+        # - None: never been subscribed
+        # - False: currently not subscribed but has been subscribed before
+        # - True: currently subscribed
+        self._connection_status = None
+        rospy.Timer(rospy.Duration(5),
+                    self._warn_never_subscribed_cb, oneshot=True)
+
+    def _post_init(self):
+        if not rospy.get_param('~lazy', True):
+            self.subscribe()
+            self._connection_status = True
+
+    def _warn_never_subscribed_cb(self, timer_event):
+        if self._connection_status is None:
+            rospy.logwarn(
+                '[{name}] subscribes topics only with'
+                " child subscribers. Set '~lazy' as False"
+                ' to have it always transport message.'
+                .format(name=rospy.get_name()))
+
+    def subscribe(self):
+        raise NotImplementedError('Please overwrite this method')
+
+    def unsubscribe(self):
+        raise NotImplementedError('Please overwrite this method')
+
+    def peer_subscribe(self, *args, **kwargs):
+        rospy.logdebug('[{topic}] is subscribed'.format(topic=args[0]))
+        if self._connection_status is not True:
+            self.subscribe()
+            self._connection_status = True
+
+    def peer_unsubscribe(self, *args, **kwargs):
+        rospy.logdebug('[{topic}] is unsubscribed'.format(topic=args[0]))
+        if not rospy.get_param('~lazy', True):
+            return  # do not unsubscribe
+        if self._connection_status in [None, False]:
+            return  # no need to unsubscribe
+        for pub in self._publishers:
+            if pub.get_num_connections() > 0:
+                break
+        else:
+            self.unsubscribe()
+            self._connection_status = False
+
+    def advertise(self, *args, **kwargs):
+        # subscriber_listener should be 'self'
+        # to detect connection and disconnection of the publishing topics
+        assert len(args) < 3 or args[2] is None
+        assert kwargs.get('subscriber_listener') is None
+        kwargs['subscriber_listener'] = self
+
+        pub = rospy.Publisher(*args, **kwargs)
+        self._publishers.append(pub)
+        return pub
diff --git a/tools/topic_tools/sample/simple_lazy_transport.py b/tools/topic_tools/sample/simple_lazy_transport.py
new file mode 100755
index 0000000..5ca457e
--- /dev/null
+++ b/tools/topic_tools/sample/simple_lazy_transport.py
@@ -0,0 +1,29 @@
+#!/usr/bin/env python
+
+import roslib.message
+import rospy
+
+from topic_tools import LazyTransport
+
+
+class SimpleLazyTransport(LazyTransport):
+    def __init__(self):
+        super(self.__class__, self).__init__()
+        msg_name = rospy.get_param('~msg_name')
+        self.msg_class = roslib.message.get_message_class(msg_name)
+        self._pub = self.advertise('~output', self.msg_class, queue_size=1)
+
+    def subscribe(self):
+        self._sub = rospy.Subscriber('~input', self.msg_class, self._process)
+
+    def unsubscribe(self):
+        self._sub.unregister()
+
+    def _process(self, img_msg):
+        self._pub.publish(img_msg)
+
+
+if __name__ == '__main__':
+    rospy.init_node('simple_transport')
+    app = SimpleLazyTransport()
+    rospy.spin()
diff --git a/tools/topic_tools/setup.py b/tools/topic_tools/setup.py
new file mode 100644
index 0000000..7073c94
--- /dev/null
+++ b/tools/topic_tools/setup.py
@@ -0,0 +1,10 @@
+from distutils.core import setup
+from catkin_pkg.python_setup import generate_distutils_setup
+
+
+setup_args = generate_distutils_setup(
+    packages=['topic_tools'],
+    package_dir={'': 'python'})
+
+
+setup(**setup_args)
diff --git a/tools/topic_tools/test/lazy_transport.test b/tools/topic_tools/test/lazy_transport.test
new file mode 100644
index 0000000..0eb186a
--- /dev/null
+++ b/tools/topic_tools/test/lazy_transport.test
@@ -0,0 +1,28 @@
+<launch>
+
+  <node pkg="rostopic" type="rostopic" name="input"
+        args="pub /input std_msgs/String 'data: spam' -r 10">
+  </node>
+
+  <node name="simple_lazy_string_transport"
+        pkg="topic_tools" type="simple_lazy_transport.py">
+    <remap from="~input" to="input" />
+    <param name="~lazy" value="true" />
+    <rosparam>
+      msg_name: std_msgs/String
+    </rosparam>
+  </node>
+
+  <test test-name="test_lazy_transport"
+        name="test_lazy_transport"
+        pkg="topic_tools" type="test_lazy_transport.py"
+        retry="3">
+    <remap from="~input" to="simple_lazy_string_transport/output" />
+    <rosparam>
+      input_topic_type: std_msgs/String
+      check_connected_topics: [simple_lazy_string_transport/output, input]
+      wait_for_connection: 3
+    </rosparam>
+  </test>
+
+</launch>
diff --git a/tools/topic_tools/test/test_lazy_transport.py b/tools/topic_tools/test/test_lazy_transport.py
new file mode 100755
index 0000000..931fe05
--- /dev/null
+++ b/tools/topic_tools/test/test_lazy_transport.py
@@ -0,0 +1,64 @@
+#!/usr/bin/env python
+
+import os
+import sys
+
+import unittest
+
+import rosgraph
+import rospy
+import rosmsg
+import roslib
+
+
+PKG = 'topic_tools'
+NAME = 'test_lazy_transport'
+
+
+class TestLazyTransport(unittest.TestCase):
+
+    def __init__(self, *args):
+        super(self.__class__, self).__init__(*args)
+        rospy.init_node(NAME)
+
+    def test_no_subscribers(self):
+        check_connected_topics = rospy.get_param('~check_connected_topics')
+        master = rosgraph.Master('/test_connection')
+        _, sub, _ = master.getSystemState()
+        # Check assumed topics are not there
+        master = rosgraph.Master('test_connection')
+        _, subscriptions, _ = master.getSystemState()
+        for check_topic in check_connected_topics:
+            for topic, sub_node in subscriptions:
+                if topic == rospy.get_namespace() + check_topic:
+                    raise ValueError('Found topic: {}'.format(check_topic))
+
+    def test_subscriber_appears(self):
+        topic_type = rospy.get_param('~input_topic_type')
+        check_connected_topics = rospy.get_param('~check_connected_topics')
+        wait_time = rospy.get_param('~wait_for_connection', 0)
+        msg_class = roslib.message.get_message_class(topic_type)
+        # Subscribe topic and bond connection
+        sub = rospy.Subscriber('~input', msg_class,
+                               self._cb_test_subscriber_appears)
+        print('Waiting for connection for {} sec.'.format(wait_time))
+        rospy.sleep(wait_time)
+        # Check assumed topics are there
+        master = rosgraph.Master('test_connection')
+        _, subscriptions, _ = master.getSystemState()
+        for check_topic in check_connected_topics:
+            for topic, sub_node in subscriptions:
+                if topic == rospy.get_namespace() + check_topic:
+                    break
+            else:
+                raise ValueError('Topic Not Found: {}'
+                                 .format(rospy.get_namespace() + check_topic))
+        sub.unregister()
+
+    def _cb_test_subscriber_appears(self, msg):
+        pass
+
+
+if __name__ == "__main__":
+    import rostest
+    rostest.rosrun(PKG, NAME, TestLazyTransport)
diff --git a/utilities/message_filters/CHANGELOG.rst b/utilities/message_filters/CHANGELOG.rst
index f730e4a..213e9c7 100644
--- a/utilities/message_filters/CHANGELOG.rst
+++ b/utilities/message_filters/CHANGELOG.rst
@@ -2,6 +2,10 @@
 Changelog for package message_filters
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.12.3 (2016-09-17)
+-------------------
+* add fast approximate time synchronization in message_filters (in pure Python) (`#802 <https://github.com/ros/ros_comm/issues/802>`_)
+
 1.12.2 (2016-06-03)
 -------------------
 * allow saving timestamp-less messages to Cache, add getLast method (`#806 <https://github.com/ros/ros_comm/pull/806>`_)
diff --git a/utilities/message_filters/package.xml b/utilities/message_filters/package.xml
index c781c0d..473e42b 100644
--- a/utilities/message_filters/package.xml
+++ b/utilities/message_filters/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>message_filters</name>
-  <version>1.12.2</version>
+  <version>1.12.3</version>
   <description>
     A set of message filters which take in messages and may output those messages at a later time, based on the conditions that filter needs met.
   </description>
diff --git a/utilities/message_filters/src/message_filters/__init__.py b/utilities/message_filters/src/message_filters/__init__.py
index 700f49d..999e6d9 100644
--- a/utilities/message_filters/src/message_filters/__init__.py
+++ b/utilities/message_filters/src/message_filters/__init__.py
@@ -34,6 +34,7 @@ import itertools
 import threading
 import rospy
 
+
 class SimpleFilter(object):
 
     def __init__(self):
@@ -202,9 +203,11 @@ class TimeSynchronizer(SimpleFilter):
 
     def connectInput(self, fs):
         self.queues = [{} for f in fs]
-        self.input_connections = [f.registerCallback(self.add, q) for (f, q) in zip(fs, self.queues)]
+        self.input_connections = [
+            f.registerCallback(self.add, q, i_q)
+            for i_q, (f, q) in enumerate(zip(fs, self.queues))]
 
-    def add(self, msg, my_queue):
+    def add(self, msg, my_queue, my_queue_index=None):
         self.lock.acquire()
         my_queue[msg.header.stamp] = msg
         while len(my_queue) > self.queue_size:
@@ -237,7 +240,7 @@ class ApproximateTimeSynchronizer(TimeSynchronizer):
         self.slop = rospy.Duration.from_sec(slop)
         self.allow_headerless = allow_headerless
 
-    def add(self, msg, my_queue):
+    def add(self, msg, my_queue, my_queue_index=None):
         if not hasattr(msg, 'header') or not hasattr(msg.header, 'stamp'):
             if not self.allow_headerless:
                 rospy.logwarn("Cannot use message filters with non-stamped messages. "
@@ -252,7 +255,31 @@ class ApproximateTimeSynchronizer(TimeSynchronizer):
         my_queue[stamp] = msg
         while len(my_queue) > self.queue_size:
             del my_queue[min(my_queue)]
-        for vv in itertools.product(*[list(q.keys()) for q in self.queues]):
+        # self.queues = [topic_0 {stamp: msg}, topic_1 {stamp: msg}, ...]
+        if my_queue_index is None:
+            search_queues = self.queues
+        else:
+            search_queues = self.queues[:my_queue_index] + \
+                self.queues[my_queue_index+1:]
+        # sort and leave only reasonable stamps for synchronization
+        stamps = []
+        for queue in search_queues:
+            topic_stamps = []
+            for s in queue:
+                stamp_delta = abs(s - stamp)
+                if stamp_delta > self.slop:
+                    continue  # far over the slop
+                topic_stamps.append((s, stamp_delta))
+            if not topic_stamps:
+                self.lock.release()
+                return
+            topic_stamps = sorted(topic_stamps, key=lambda x: x[1])
+            stamps.append(topic_stamps)
+        for vv in itertools.product(*[zip(*s)[0] for s in stamps]):
+            vv = list(vv)
+            # insert the new message
+            if my_queue_index is not None:
+                vv.insert(my_queue_index, stamp)
             qt = list(zip(self.queues, vv))
             if ( ((max(vv) - min(vv)) < self.slop) and
                 (len([1 for q,t in qt if t not in q]) == 0) ):
@@ -260,4 +287,5 @@ class ApproximateTimeSynchronizer(TimeSynchronizer):
                 self.signalMessage(*msgs)
                 for q,t in qt:
                     del q[t]
+                break  # fast finish after the synchronization
         self.lock.release()
diff --git a/utilities/roslz4/CHANGELOG.rst b/utilities/roslz4/CHANGELOG.rst
index 483849f..022e913 100644
--- a/utilities/roslz4/CHANGELOG.rst
+++ b/utilities/roslz4/CHANGELOG.rst
@@ -2,6 +2,10 @@
 Changelog for package roslz4
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.12.3 (2016-09-17)
+-------------------
+* set lz4_FOUND in order to continue using it with catkin_package(DEPENDS) (`ros/catkin#813 <https://github.com/ros/catkin/issues/813>`_)
+
 1.12.2 (2016-06-03)
 -------------------
 
diff --git a/utilities/roslz4/CMakeLists.txt b/utilities/roslz4/CMakeLists.txt
index ab1e99f..68f65f7 100644
--- a/utilities/roslz4/CMakeLists.txt
+++ b/utilities/roslz4/CMakeLists.txt
@@ -17,6 +17,7 @@ find_library(lz4_LIBRARIES NAMES lz4)
 if (NOT lz4_LIBRARIES)
   message(FATAL_ERROR "lz4 library not found")
 endif()
+set(lz4_FOUND TRUE)
 
 catkin_python_setup()
 
@@ -41,7 +42,7 @@ include_directories(${PYTHON_INCLUDE_PATH})
 add_library(roslz4_py src/_roslz4module.c)
 set_source_files_properties(
   src/_roslz4module.c
-PROPERTIES COMPILE_FLAGS "-Wno-missing-field-initializers -Wno-unused-variable")
+PROPERTIES COMPILE_FLAGS "-Wno-missing-field-initializers -Wno-unused-variable -Wno-strict-aliasing")
 set_target_properties(
   roslz4_py PROPERTIES OUTPUT_NAME roslz4 PREFIX "_" SUFFIX ".so"
   LIBRARY_OUTPUT_DIRECTORY ${CATKIN_DEVEL_PREFIX}/${PYTHON_INSTALL_DIR}/roslz4)
diff --git a/utilities/roslz4/package.xml b/utilities/roslz4/package.xml
index 6ef632a..4621091 100644
--- a/utilities/roslz4/package.xml
+++ b/utilities/roslz4/package.xml
@@ -1,7 +1,7 @@
 <?xml version="1.0"?>
 <package>
   <name>roslz4</name>
-  <version>1.12.2</version>
+  <version>1.12.3</version>
   <description>
     A Python and C++ implementation of the LZ4 streaming format.  Large data
     streams are split into blocks which are compressed using the very fast LZ4
diff --git a/utilities/roswtf/CHANGELOG.rst b/utilities/roswtf/CHANGELOG.rst
index c055fba..0d046f9 100644
--- a/utilities/roswtf/CHANGELOG.rst
+++ b/utilities/roswtf/CHANGELOG.rst
@@ -2,6 +2,9 @@
 Changelog for package roswtf
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.12.3 (2016-09-17)
+-------------------
+
 1.12.2 (2016-06-03)
 -------------------
 
diff --git a/utilities/roswtf/package.xml b/utilities/roswtf/package.xml
index 8f4dcfe..4bc7c0a 100644
--- a/utilities/roswtf/package.xml
+++ b/utilities/roswtf/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>roswtf</name>
-  <version>1.12.2</version>
+  <version>1.12.3</version>
   <description>
      roswtf is a tool for diagnosing issues with a running ROS system. Think of it as a FAQ implemented in code.
   </description>
diff --git a/utilities/roswtf/test/check_roswtf_command_line_online.py b/utilities/roswtf/test/check_roswtf_command_line_online.py
index f4a9fe2..46676c0 100755
--- a/utilities/roswtf/test/check_roswtf_command_line_online.py
+++ b/utilities/roswtf/test/check_roswtf_command_line_online.py
@@ -97,6 +97,12 @@ class TestRostopicOnline(unittest.TestCase):
             pass
         else:
             paths.append(path)
+        try:
+            path = rospack.get_path('gennodejs')
+        except rospkg.ResourceNotFound:
+            pass
+        else:
+            paths.append(path)
         env['ROS_PACKAGE_PATH'] = os.pathsep.join(paths)
 
         cwd  = rospack.get_path('roswtf')
diff --git a/utilities/roswtf/test/test_roswtf_command_line_offline.py b/utilities/roswtf/test/test_roswtf_command_line_offline.py
index e91b055..81ea381 100644
--- a/utilities/roswtf/test/test_roswtf_command_line_offline.py
+++ b/utilities/roswtf/test/test_roswtf_command_line_offline.py
@@ -86,6 +86,12 @@ class TestRoswtfOffline(unittest.TestCase):
             pass
         else:
             paths.append(path)
+        try:
+            path = rospack.get_path('gennodejs')
+        except rospkg.ResourceNotFound:
+            pass
+        else:
+            paths.append(path)
         env['ROS_PACKAGE_PATH'] = os.pathsep.join(paths)
 
         cwd  = get_roswtf_path()
diff --git a/utilities/xmlrpcpp/CHANGELOG.rst b/utilities/xmlrpcpp/CHANGELOG.rst
index 4d77ae5..2613407 100644
--- a/utilities/xmlrpcpp/CHANGELOG.rst
+++ b/utilities/xmlrpcpp/CHANGELOG.rst
@@ -2,6 +2,9 @@
 Changelog for package xmlrpcpp
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.12.3 (2016-09-17)
+-------------------
+
 1.12.2 (2016-06-03)
 -------------------
 
diff --git a/utilities/xmlrpcpp/package.xml b/utilities/xmlrpcpp/package.xml
index 57a855e..afc2a72 100644
--- a/utilities/xmlrpcpp/package.xml
+++ b/utilities/xmlrpcpp/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>xmlrpcpp</name>
-  <version>1.12.2</version>
+  <version>1.12.3</version>
   <description>
     XmlRpc++ is a C++ implementation of the XML-RPC protocol. This version is
     heavily modified from the package available on SourceForge in order to

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



More information about the debian-science-commits mailing list