[ros-comm] 01/01: Imported Upstream version 1.11.11

Jochen Sprickerhof jspricke-guest at moszumanska.debian.org
Thu Apr 23 21:27:13 UTC 2015


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

jspricke-guest pushed a commit to annotated tag upstream/1.11.11
in repository ros-comm.

commit 3c6b52aae84c3fc7c95197dda36d9e2d48ae5add
Author: Jochen Sprickerhof <git at jochen.sprickerhof.de>
Date:   Thu Apr 23 23:01:26 2015 +0200

    Imported Upstream version 1.11.11
---
 clients/roscpp/CHANGELOG.rst                       |   8 +
 clients/roscpp/include/ros/node_handle.h           | 164 +++++++++++++++---
 clients/roscpp/include/ros/param.h                 |  39 +++++
 clients/roscpp/package.xml                         |   2 +-
 clients/roscpp/src/libros/statistics.cpp           |  19 ++-
 clients/roscpp/src/libros/transport/transport.cpp  |   1 +
 .../src/libros/transport_subscriber_link.cpp       |   1 +
 clients/rospy/CHANGELOG.rst                        |   7 +
 clients/rospy/package.xml                          |   2 +-
 clients/rospy/scripts/rosconsole                   |   3 +
 clients/rospy/setup.py                             |   1 +
 clients/rospy/src/rospy/core.py                    |   4 +-
 clients/rospy/src/rospy/impl/tcpros_pubsub.py      |  14 +-
 .../rospy/src/rospy/logger_level_service_caller.py | 147 +++++++++++++++++
 clients/rospy/src/rospy/msg.py                     |  12 +-
 clients/rospy/src/rospy/rosconsole.py              | 183 +++++++++++++++++++++
 clients/rospy/src/rospy/timer.py                   |  33 +++-
 clients/rospy/src/rospy/topics.py                  |   9 +
 ros_comm/CHANGELOG.rst                             |   3 +
 ros_comm/package.xml                               |   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               |   2 +
 ...amped_topic_statistics_with_empty_timestamp.xml |   5 +
 test/test_roscpp/test/src/CMakeLists.txt           |   6 +
 test/test_roscpp/test/src/params.cpp               |  32 ++++
 .../stamped_topic_statistics_empty_timestamp.cpp   |  71 ++++++++
 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/CMakeLists.txt                     |   1 +
 test/test_rospy/msg/Empty.msg                      |   0
 test/test_rospy/package.xml                        |   2 +-
 test/test_rospy/test/unit/test_rospy_msg.py        |   6 +-
 test/test_rosservice/package.xml                   |   2 +-
 tools/rosbag/CHANGELOG.rst                         |   4 +
 tools/rosbag/include/rosbag/player.h               |   3 +
 tools/rosbag/package.xml                           |   2 +-
 tools/rosbag/src/play.cpp                          |  15 +-
 tools/rosbag/src/player.cpp                        |  24 ++-
 tools/rosbag/src/rosbag/rosbag_main.py             |  21 ++-
 tools/rosbag_storage/CHANGELOG.rst                 |   4 +
 tools/rosbag_storage/CMakeLists.txt                |   3 +
 tools/rosbag_storage/package.xml                   |   2 +-
 tools/rosconsole/CHANGELOG.rst                     |   4 +
 tools/rosconsole/include/ros/console.h             |  41 +++++
 .../include/rosconsole/macros_generated.h          |  40 +++++
 tools/rosconsole/package.xml                       |   2 +-
 tools/rosconsole/scripts/generate_macros.py        |  19 ++-
 tools/rosconsole/test/utest.cpp                    |  83 ++++++++++
 tools/rosgraph/CHANGELOG.rst                       |   3 +
 tools/rosgraph/package.xml                         |   2 +-
 tools/roslaunch/CHANGELOG.rst                      |   3 +
 tools/roslaunch/package.xml                        |   2 +-
 tools/rosmaster/CHANGELOG.rst                      |   3 +
 tools/rosmaster/package.xml                        |   2 +-
 tools/rosmsg/CHANGELOG.rst                         |   3 +
 tools/rosmsg/package.xml                           |   2 +-
 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                     |   3 +
 tools/rosservice/package.xml                       |   2 +-
 tools/rostest/CHANGELOG.rst                        |   4 +
 tools/rostest/cmake/rostest-extras.cmake.em        |   4 +-
 tools/rostest/package.xml                          |   2 +-
 tools/rostopic/CHANGELOG.rst                       |   3 +
 tools/rostopic/package.xml                         |   2 +-
 tools/topic_tools/CHANGELOG.rst                    |   3 +
 tools/topic_tools/package.xml                      |   2 +-
 utilities/message_filters/CHANGELOG.rst            |   4 +
 utilities/message_filters/CMakeLists.txt           |   1 +
 utilities/message_filters/package.xml              |   2 +-
 .../src/message_filters/__init__.py                |  56 ++++++-
 .../test/test_message_filters_cache.py             | 127 ++++++++++++++
 utilities/roslz4/CHANGELOG.rst                     |   4 +
 utilities/roslz4/package.xml                       |   2 +-
 utilities/roslz4/src/roslz4/__init__.py            |   2 +-
 utilities/roswtf/CHANGELOG.rst                     |   4 +
 utilities/roswtf/package.xml                       |   2 +-
 utilities/roswtf/src/roswtf/network.py             |   6 +-
 utilities/xmlrpcpp/CHANGELOG.rst                   |   3 +
 utilities/xmlrpcpp/package.xml                     |   2 +-
 89 files changed, 1250 insertions(+), 89 deletions(-)

diff --git a/clients/roscpp/CHANGELOG.rst b/clients/roscpp/CHANGELOG.rst
index 73241e6..8896844 100644
--- a/clients/roscpp/CHANGELOG.rst
+++ b/clients/roscpp/CHANGELOG.rst
@@ -2,6 +2,14 @@
 Changelog for package roscpp
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.11.11 (2015-04-16)
+--------------------
+* fix memory leak in transport constructor (`#570 <https://github.com/ros/ros_comm/pull/570>`_)
+* fix computation of stddev in statistics (`#556 <https://github.com/ros/ros_comm/pull/556>`_)
+* fix empty connection header topic (`#543 <https://github.com/ros/ros_comm/issues/543>`_)
+* alternative API to get parameter values (`#592 <https://github.com/ros/ros_comm/pull/592>`_)
+* add getCached() for float parameters (`#584 <https://github.com/ros/ros_comm/pull/584>`_)
+
 1.11.10 (2014-12-22)
 --------------------
 * fix various defects reported by coverity
diff --git a/clients/roscpp/include/ros/node_handle.h b/clients/roscpp/include/ros/node_handle.h
index 995571d..1c0da03 100644
--- a/clients/roscpp/include/ros/node_handle.h
+++ b/clients/roscpp/include/ros/node_handle.h
@@ -289,7 +289,9 @@ namespace ros
    * \return On success, a Publisher that, when it goes out of scope, will automatically release a reference
    * on this advertisement.  On failure, an empty Publisher which can be checked with:
 \verbatim
-if (handle)
+ros::NodeHandle nodeHandle;
+ros::publisher pub = nodeHandle.advertise<std_msgs::Empty>("my_topic", 1, (ros::SubscriberStatusCallback)callback);
+if (pub)  // Enter if publisher is valid
 {
 ...
 }
@@ -323,7 +325,11 @@ if (handle)
    * \return On success, a Publisher that, when it goes out of scope, will automatically release a reference
    * on this advertisement.  On failure, an empty Publisher which can be checked with:
 \verbatim
-if (handle)
+ros::NodeHandle nodeHandle;
+ros::AdvertiseOptions ops;
+...
+ros::publisher pub = nodeHandle.advertise(ops);
+if (pub)  // Enter if publisher is valid
 {
 ...
 }
@@ -367,7 +373,11 @@ ros::Subscriber sub = handle.subscribe("my_topic", 1, &Foo::callback, &foo_objec
    * \return On success, a Subscriber that, when all copies of it go out of scope, will unsubscribe from this topic.
    * On failure, an empty Subscriber which can be checked with:
 \verbatim
-if (handle)
+ros::NodeHandle nodeHandle;
+void Foo::callback(const std_msgs::Empty::ConstPtr& message) {}
+boost::shared_ptr<Foo> foo_object(new Foo);
+ros::Subscriber sub = nodeHandle.subscribe("my_topic", 1, &Foo::callback, foo_object);
+if (sub)  // Enter if subscriber is valid
 {
 ...
 }
@@ -426,7 +436,11 @@ ros::Subscriber sub = handle.subscribe("my_topic", 1, &Foo::callback, &foo_objec
    * \return On success, a Subscriber that, when all copies of it go out of scope, will unsubscribe from this topic.
    * On failure, an empty Subscriber which can be checked with:
 \verbatim
-if (handle)
+ros::NodeHandle nodeHandle;
+void Foo::callback(const std_msgs::Empty::ConstPtr& message) {}
+boost::shared_ptr<Foo> foo_object(new Foo);
+ros::Subscriber sub = nodeHandle.subscribe("my_topic", 1, &Foo::callback, foo_object);
+if (sub)  // Enter if subscriber is valid
 {
 ...
 }
@@ -486,7 +500,11 @@ ros::Subscriber sub = handle.subscribe("my_topic", 1, &Foo::callback, foo_object
    * \return On success, a Subscriber that, when all copies of it go out of scope, will unsubscribe from this topic.
    * On failure, an empty Subscriber which can be checked with:
 \verbatim
-if (handle)
+ros::NodeHandle nodeHandle;
+void Foo::callback(const std_msgs::Empty::ConstPtr& message) {}
+boost::shared_ptr<Foo> foo_object(new Foo);
+ros::Subscriber sub = nodeHandle.subscribe("my_topic", 1, &Foo::callback, foo_object);
+if (sub)  // Enter if subscriber is valid
 {
 ...
 }
@@ -547,7 +565,11 @@ ros::Subscriber sub = handle.subscribe("my_topic", 1, &Foo::callback, foo_object
    * \return On success, a Subscriber that, when all copies of it go out of scope, will unsubscribe from this topic.
    * On failure, an empty Subscriber which can be checked with:
 \verbatim
-if (handle)
+ros::NodeHandle nodeHandle;
+void Foo::callback(const std_msgs::Empty::ConstPtr& message) {}
+boost::shared_ptr<Foo> foo_object(new Foo);
+ros::Subscriber sub = nodeHandle.subscribe("my_topic", 1, &Foo::callback, foo_object);
+if (sub)  // Enter if subscriber is valid
 {
 ...
 }
@@ -606,7 +628,10 @@ ros::Subscriber sub = handle.subscribe("my_topic", 1, callback);
    * \return On success, a Subscriber that, when all copies of it go out of scope, will unsubscribe from this topic.
    * On failure, an empty Subscriber which can be checked with:
 \verbatim
-if (handle)
+void callback(const std_msgs::Empty::ConstPtr& message){...}
+ros::NodeHandle nodeHandle;
+ros::Subscriber sub = nodeHandle.subscribe("my_topic", 1, callback);
+if (sub)  // Enter if subscriber is valid
 {
 ...
 }
@@ -651,7 +676,10 @@ ros::Subscriber sub = handle.subscribe("my_topic", 1, callback);
    * \return On success, a Subscriber that, when all copies of it go out of scope, will unsubscribe from this topic.
    * On failure, an empty Subscriber which can be checked with:
 \verbatim
-if (handle)
+void callback(const std_msgs::Empty::ConstPtr& message){...}
+ros::NodeHandle nodeHandle;
+ros::Subscriber sub = nodeHandle.subscribe("my_topic", 1, callback);
+if (sub)  // Enter if subscriber is valid
 {
 ...
 }
@@ -694,7 +722,10 @@ if (handle)
    * \return On success, a Subscriber that, when all copies of it go out of scope, will unsubscribe from this topic.
    * On failure, an empty Subscriber which can be checked with:
 \verbatim
-if (handle)
+void callback(const std_msgs::Empty::ConstPtr& message){...}
+ros::NodeHandle nodeHandle;
+ros::Subscriber sub = nodeHandle.subscribe("my_topic", 1, callback);
+if (sub)  // Enter if subscriber is valid
 {
 ...
 }
@@ -740,7 +771,10 @@ if (handle)
    * \return On success, a Subscriber that, when all copies of it go out of scope, will unsubscribe from this topic.
    * On failure, an empty Subscriber which can be checked with:
 \verbatim
-if (handle)
+void callback(const std_msgs::Empty::ConstPtr& message){...}
+ros::NodeHandle nodeHandle;
+ros::Subscriber sub = nodeHandle.subscribe("my_topic", 1, callback);
+if (sub)  // Enter if subscriber is valid
 {
 ...
 }
@@ -774,7 +808,11 @@ if (handle)
    * \return On success, a Subscriber that, when all copies of it go out of scope, will unsubscribe from this topic.
    * On failure, an empty Subscriber which can be checked with:
 \verbatim
-if (handle)
+SubscribeOptions ops;
+...
+ros::NodeHandle nodeHandle;
+ros::Subscriber sub = nodeHandle.subscribe(ops);
+if (sub)  // Enter if subscriber is valid
 {
 ...
 }
@@ -810,7 +848,14 @@ ros::ServiceServer service = handle.advertiseService("my_service", &Foo::callbac
    * \return On success, a ServiceServer that, when all copies of it go out of scope, will unadvertise this service.
    * On failure, an empty ServiceServer which can be checked with:
 \verbatim
-if (handle)
+bool Foo::callback(std_srvs::Empty& request, std_srvs::Empty& response)
+{
+  return true;
+}
+ros::NodeHandle nodeHandle;
+Foo foo_object;
+ros::ServiceServer service = nodeHandle.advertiseService("my_service", &Foo::callback, &foo_object);
+if (service)  // Enter if advertised service is valid
 {
 ...
 }
@@ -848,7 +893,14 @@ ros::ServiceServer service = handle.advertiseService("my_service", &Foo::callbac
    * \return On success, a ServiceServer that, when all copies of it go out of scope, will unadvertise this service.
    * On failure, an empty ServiceServer which can be checked with:
 \verbatim
-if (handle)
+bool Foo::callback(std_srvs::Empty& request, std_srvs::Empty& response)
+{
+  return true;
+}
+ros::NodeHandle nodeHandle;
+Foo foo_object;
+ros::ServiceServer service = nodeHandle.advertiseService("my_service", &Foo::callback, &foo_object);
+if (service)  // Enter if advertised service is valid
 {
 ...
 }
@@ -887,7 +939,14 @@ ros::ServiceServer service = handle.advertiseService("my_service", &Foo::callbac
    * \return On success, a ServiceServer that, when all copies of it go out of scope, will unadvertise this service.
    * On failure, an empty ServiceServer which can be checked with:
 \verbatim
-if (handle)
+bool Foo::callback(std_srvs::Empty& request, std_srvs::Empty& response)
+{
+  return true;
+}
+ros::NodeHandle nodeHandle;
+Foo foo_object;
+ros::ServiceServer service = nodeHandle.advertiseService("my_service", &Foo::callback, &foo_object);
+if (service)  // Enter if advertised service is valid
 {
 ...
 }
@@ -927,7 +986,14 @@ ros::ServiceServer service = handle.advertiseService("my_service", &Foo::callbac
    * \return On success, a ServiceServer that, when all copies of it go out of scope, will unadvertise this service.
    * On failure, an empty ServiceServer which can be checked with:
 \verbatim
-if (handle)
+bool Foo::callback(std_srvs::Empty& request, std_srvs::Empty& response)
+{
+  return true;
+}
+ros::NodeHandle nodeHandle;
+Foo foo_object;
+ros::ServiceServer service = nodeHandle.advertiseService("my_service", &Foo::callback, &foo_object);
+if (service)  // Enter if advertised service is valid
 {
 ...
 }
@@ -964,7 +1030,14 @@ ros::ServiceServer service = handle.advertiseService("my_service", callback);
    * \return On success, a ServiceServer that, when all copies of it go out of scope, will unadvertise this service.
    * On failure, an empty ServiceServer which can be checked with:
 \verbatim
-if (handle)
+bool Foo::callback(std_srvs::Empty& request, std_srvs::Empty& response)
+{
+  return true;
+}
+ros::NodeHandle nodeHandle;
+Foo foo_object;
+ros::ServiceServer service = nodeHandle.advertiseService("my_service", callback);
+if (service)  // Enter if advertised service is valid
 {
 ...
 }
@@ -1000,7 +1073,14 @@ ros::ServiceServer service = handle.advertiseService("my_service", callback);
    * \return On success, a ServiceServer that, when all copies of it go out of scope, will unadvertise this service.
    * On failure, an empty ServiceServer which can be checked with:
 \verbatim
-if (handle)
+bool Foo::callback(std_srvs::Empty& request, std_srvs::Empty& response)
+{
+  return true;
+}
+ros::NodeHandle nodeHandle;
+Foo foo_object;
+ros::ServiceServer service = nodeHandle.advertiseService("my_service", callback);
+if (service)  // Enter if advertised service is valid
 {
 ...
 }
@@ -1034,7 +1114,14 @@ if (handle)
    * \return On success, a ServiceServer that, when all copies of it go out of scope, will unadvertise this service.
    * On failure, an empty ServiceServer which can be checked with:
 \verbatim
-if (handle)
+bool Foo::callback(std_srvs::Empty& request, std_srvs::Empty& response)
+{
+  return true;
+}
+ros::NodeHandle nodeHandle;
+Foo foo_object;
+ros::ServiceServer service = nodeHandle.advertiseService("my_service", callback);
+if (service)  // Enter if advertised service is valid
 {
 ...
 }
@@ -1072,7 +1159,14 @@ if (handle)
    * \return On success, a ServiceServer that, when all copies of it go out of scope, will unadvertise this service.
    * On failure, an empty ServiceServer which can be checked with:
 \verbatim
-if (handle)
+bool Foo::callback(std_srvs::Empty& request, std_srvs::Empty& response)
+{
+  return true;
+}
+ros::NodeHandle nodeHandle;
+Foo foo_object;
+ros::ServiceServer service = nodeHandle.advertiseService("my_service", callback);
+if (service)  // Enter if advertised service is valid
 {
 ...
 }
@@ -1101,7 +1195,11 @@ if (handle)
    * \return On success, a ServiceServer that, when all copies of it go out of scope, will unadvertise this service.
    * On failure, an empty ServiceServer which can be checked with:
 \verbatim
-if (handle)
+AdvertiseServiceOptions ops;
+...
+ros::NodeHandle nodeHandle;
+ros::ServiceServer service = nodeHandle.advertiseService(ops);
+if (service)  // Enter if advertised service is valid
 {
 ...
 }
@@ -1923,6 +2021,32 @@ if (handle)
   }
 
   /**
+   * \brief Return value from parameter server, or default if unavailable.
+   *
+   * This method tries to retrieve the indicated parameter value from the
+   * parameter server. If the parameter cannot be retrieved, \c default_val
+   * is returned instead.
+   *
+   * \param param_name The key to be searched on the parameter server.
+   *
+   * \param default_val Value to return if the server doesn't contain this
+   * parameter.
+   *
+   * \return The parameter value retrieved from the parameter server, or
+   * \c default_val if unavailable.
+   *
+   * \throws InvalidNameException If the parameter key begins with a tilde,
+   * or is an otherwise invalid graph resource name.
+   */
+  template<typename T>
+  T param(const std::string& param_name, const T& default_val)
+  {
+      T param_val;
+      param(param_name, param_val, default_val);
+      return param_val;
+  }
+
+  /**
    * \brief Shutdown every handle created through this NodeHandle.
    *
    * This method will unadvertise every topic and service advertisement,
diff --git a/clients/roscpp/include/ros/param.h b/clients/roscpp/include/ros/param.h
index 37beb9b..a015043 100644
--- a/clients/roscpp/include/ros/param.h
+++ b/clients/roscpp/include/ros/param.h
@@ -244,6 +244,20 @@ ROSCPP_DECL bool getCached(const std::string& key, std::string& s);
  * \throws InvalidNameException if the key is not a valid graph resource name
  */
 ROSCPP_DECL bool getCached(const std::string& key, double& d);
+/** \brief Get a float value from the parameter server, with local caching
+ *
+ * This function will cache parameters locally, and subscribe for updates from
+ * the parameter server.  Once the parameter is retrieved for the first time
+ * no subsequent getCached() calls with the same key will query the master --
+ * they will instead look up in the local cache.
+ *
+ * \param key The key to be used in the parameter server's dictionary
+ * \param[out] f Storage for the retrieved value.
+ *
+ * \return true if the parameter value was retrieved, false otherwise
+ * \throws InvalidNameException if the key is not a valid graph resource name
+ */
+ROSCPP_DECL bool getCached(const std::string& key, float& f);
 /** \brief Get an integer value from the parameter server, with local caching
  *
  * This function will cache parameters locally, and subscribe for updates from
@@ -596,6 +610,31 @@ void param(const std::string& param_name, T& param_val, const T& default_val)
   param_val = default_val;
 }
 
+/**
+ * \brief Return value from parameter server, or default if unavailable.
+ *
+ * This method tries to retrieve the indicated parameter value from the
+ * parameter server. If the parameter cannot be retrieved, \c default_val
+ * is returned instead.
+ *
+ * \param param_name The key to be searched on the parameter server.
+ *
+ * \param default_val Value to return if the server doesn't contain this
+ * parameter.
+ *
+ * \return The parameter value retrieved from the parameter server, or
+ * \c default_val if unavailable.
+ *
+ * \throws InvalidNameException If the key is not a valid graph resource name.
+ */
+template<typename T>
+T param(const std::string& param_name, const T& default_val)
+{
+  T param_val;
+  param(param_name, param_val, default_val);
+  return param_val;
+}
+
 } // namespace param
 
 } // namespace ros
diff --git a/clients/roscpp/package.xml b/clients/roscpp/package.xml
index 8743c34..65b5a84 100644
--- a/clients/roscpp/package.xml
+++ b/clients/roscpp/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>roscpp</name>
-  <version>1.11.10</version>
+  <version>1.11.11</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/src/libros/statistics.cpp b/clients/roscpp/src/libros/statistics.cpp
index f5a3700..634bc80 100644
--- a/clients/roscpp/src/libros/statistics.cpp
+++ b/clients/roscpp/src/libros/statistics.cpp
@@ -144,13 +144,26 @@ void StatisticsLogger::callback(const boost::shared_ptr<M_string>& connection_he
 
       msg.stamp_age_mean *= 1.0 / stats.age_list.size();
 
-      msg.stamp_age_stddev = ros::Duration(0);
+      double stamp_age_variance = 0.0;
       for(std::list<ros::Duration>::iterator it = stats.age_list.begin(); it != stats.age_list.end(); it++)
       {
         ros::Duration t = msg.stamp_age_mean - *it;
-        msg.stamp_age_stddev += ros::Duration(t.toSec() * t.toSec());
+        stamp_age_variance += t.toSec() * t.toSec();
+      }
+      double stamp_age_stddev = sqrt(stamp_age_variance / stats.age_list.size());
+      try
+      {
+        msg.stamp_age_stddev = ros::Duration(stamp_age_stddev);
+      }
+      catch(std::runtime_error& e)
+      {
+        msg.stamp_age_stddev = ros::Duration(0);
+        ROS_WARN_STREAM("Error updating stamp_age_stddev for topic [" << topic << "]"
+          << " from node [" << callerid << "],"
+          << " likely due to the time between the mean stamp age and this message being exceptionally large."
+          << " Exception was: " << e.what());
+        ROS_DEBUG_STREAM("Mean stamp age was: " << msg.stamp_age_mean << " - std_dev of: " << stamp_age_stddev);
       }
-      msg.stamp_age_stddev = ros::Duration(sqrt(msg.stamp_age_stddev.toSec() / stats.age_list.size()));
 
     }
     else
diff --git a/clients/roscpp/src/libros/transport/transport.cpp b/clients/roscpp/src/libros/transport/transport.cpp
index deeb4c7..b4c3fbb 100644
--- a/clients/roscpp/src/libros/transport/transport.cpp
+++ b/clients/roscpp/src/libros/transport/transport.cpp
@@ -100,6 +100,7 @@ Transport::Transport()
     }
     allowed_hosts_.push_back(std::string(addr));
   }
+  freeifaddrs(ifaddr);
 #endif
 }
 
diff --git a/clients/roscpp/src/libros/transport_subscriber_link.cpp b/clients/roscpp/src/libros/transport_subscriber_link.cpp
index c5b7f3a..b26ae75 100644
--- a/clients/roscpp/src/libros/transport_subscriber_link.cpp
+++ b/clients/roscpp/src/libros/transport_subscriber_link.cpp
@@ -111,6 +111,7 @@ bool TransportSubscriberLink::handleHeader(const Header& header)
   m["message_definition"] = pt->getMessageDefinition();
   m["callerid"] = this_node::getName();
   m["latching"] = pt->isLatching() ? "1" : "0";
+  m["topic"] = topic_;
   connection_->writeHeader(m, boost::bind(&TransportSubscriberLink::onHeaderWritten, this, _1));
 
   pt->addSubscriberLink(shared_from_this());
diff --git a/clients/rospy/CHANGELOG.rst b/clients/rospy/CHANGELOG.rst
index ff89619..749ada0 100644
--- a/clients/rospy/CHANGELOG.rst
+++ b/clients/rospy/CHANGELOG.rst
@@ -2,6 +2,13 @@
 Changelog for package rospy
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.11.11 (2015-04-16)
+--------------------
+* add rosconsole command line tool to change logger levels (`#576 <https://github.com/ros/ros_comm/pull/576>`_)
+* add accessor for remaining time of the Rate class (`#588 <https://github.com/ros/ros_comm/pull/588>`_)
+* fix high latency when using asynchronous publishing (`#547 <https://github.com/ros/ros_comm/issues/547>`_)
+* fix error handling when publishing on Empty topic (`#566 <https://github.com/ros/ros_comm/pull/566>`_)
+
 1.11.10 (2014-12-22)
 --------------------
 * add specific exception for time jumping backwards (`#485 <https://github.com/ros/ros_comm/issues/485>`_)
diff --git a/clients/rospy/package.xml b/clients/rospy/package.xml
index 83a7026..c3492c5 100644
--- a/clients/rospy/package.xml
+++ b/clients/rospy/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>rospy</name>
-  <version>1.11.10</version>
+  <version>1.11.11</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/scripts/rosconsole b/clients/rospy/scripts/rosconsole
new file mode 100755
index 0000000..c2828c4
--- /dev/null
+++ b/clients/rospy/scripts/rosconsole
@@ -0,0 +1,3 @@
+#!/usr/bin/env python
+from rospy import rosconsole
+rosconsole.main()
diff --git a/clients/rospy/setup.py b/clients/rospy/setup.py
index 2ad36c8..64f989a 100644
--- a/clients/rospy/setup.py
+++ b/clients/rospy/setup.py
@@ -6,6 +6,7 @@ from catkin_pkg.python_setup import generate_distutils_setup
 d = generate_distutils_setup(
     packages=['rospy', 'rospy.impl'],
     package_dir={'': 'src'},
+    scripts=['scripts/rosconsole'],
     requires=['genpy', 'numpy', 'rosgraph', 'roslib', 'rospkg']
 )
 
diff --git a/clients/rospy/src/rospy/core.py b/clients/rospy/src/rospy/core.py
index e0911b0..b2ae84d 100644
--- a/clients/rospy/src/rospy/core.py
+++ b/clients/rospy/src/rospy/core.py
@@ -346,8 +346,8 @@ def add_client_shutdown_hook(h):
     L{add_shutdown_hook} and L{add_preshutdown_hooks}, these methods
     will be called before any rospy internal shutdown code.
     
-    @param h: function that takes in a single string argument (shutdown reason)
-    @type  h: fn(str)
+    @param h: function with zero args
+    @type  h: fn()
     """
     _add_shutdown_hook(h, _client_shutdown_hooks)
 
diff --git a/clients/rospy/src/rospy/impl/tcpros_pubsub.py b/clients/rospy/src/rospy/impl/tcpros_pubsub.py
index dce1aae..8cd05f6 100644
--- a/clients/rospy/src/rospy/impl/tcpros_pubsub.py
+++ b/clients/rospy/src/rospy/impl/tcpros_pubsub.py
@@ -255,14 +255,18 @@ class TCPROSHandler(rospy.impl.transport.ProtocolHandler):
         t = threading.Thread(name=resolved_name, target=robust_connect_subscriber, args=(conn, dest_addr, dest_port, pub_uri, sub.receive_callback,resolved_name))
         # don't enable this just yet, need to work on this logic
         #rospy.core._add_shutdown_thread(t)
-        t.start()
 
         # Attach connection to _SubscriberImpl
         if sub.add_connection(conn): #pass tcp connection to handler
+            # since the thread might cause the connection to close
+            # it should only be started after the connection has been added to the subscriber
+            # https://github.com/ros/ros_comm/issues/544
+            t.start()
             return 1, "Connected topic[%s]. Transport impl[%s]"%(resolved_name, conn.__class__.__name__), dest_port
         else:
+            # _SubscriberImpl already closed or duplicate subscriber created
             conn.close()
-            return 0, "ERROR: Race condition failure: duplicate topic subscriber [%s] was created"%(resolved_name), 0
+            return 0, "ERROR: Race condition failure creating topic subscriber [%s]"%(resolved_name), 0
 
     def supports(self, protocol):
         """
@@ -382,12 +386,16 @@ class QueuedConnection(object):
 
         self._lock = threading.Lock()
         self._cond_data_available = threading.Condition(self._lock)
+        self._connection.set_cleanup_callback(self._closed_connection_callback)
         self._queue = []
         self._error = None
 
         self._thread = threading.Thread(target=self._run)
         self._thread.start()
 
+    def _closed_connection_callback(self, connection):
+        self._cond_data_available.notify()
+
     def __getattr__(self, name):
         if name.startswith('__'):
             raise AttributeError(name)
@@ -415,7 +423,7 @@ class QueuedConnection(object):
             with self._lock:
                 # wait for available data
                 while not self._queue and not self._connection.done:
-                    self._cond_data_available.wait(1.0)
+                    self._cond_data_available.wait()
                 # take all data from queue for processing outside of the lock
                 if self._queue:
                     queue = self._queue
diff --git a/clients/rospy/src/rospy/logger_level_service_caller.py b/clients/rospy/src/rospy/logger_level_service_caller.py
new file mode 100644
index 0000000..f274512
--- /dev/null
+++ b/clients/rospy/src/rospy/logger_level_service_caller.py
@@ -0,0 +1,147 @@
+# Software License Agreement (BSD License)
+#
+# Copyright (c) 2015, Chris Mansley, Open Source Robotics Foundation, 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.
+
+import rosgraph
+import rosnode
+import rospy
+import rosservice
+
+
+class ROSConsoleException(Exception):
+
+    """Base exception class of rosconsole-related errors."""
+
+    pass
+
+
+class LoggerLevelServiceCaller(object):
+
+    """
+    Handles service calls for getting lists of nodes and loggers.
+
+    Also handles sending requests to change logger levels.
+    """
+
+    def __init__(self):
+        pass
+
+    def get_levels(self):
+        # Declare level names lower-case, because that's how they are returned
+        # from the service call.
+        return ['debug', 'info', 'warn', 'error', 'fatal']
+
+    def get_loggers(self, node):
+        self._refresh_loggers(node)
+        return self._current_loggers
+
+    def get_node_names(self):
+        """
+        Get a list of available services via a ros service call.
+
+        :returns: a list of all nodes that provide the set_logger_level service, ''list(str)''
+        """
+        set_logger_level_nodes = []
+        nodes = rosnode.get_node_names()
+        for name in sorted(nodes):
+            for service in rosservice.get_service_list(name):
+                if service == name + '/set_logger_level':
+                    set_logger_level_nodes.append(name)
+        return set_logger_level_nodes
+
+    def _refresh_loggers(self, node):
+        """
+        Store a list of loggers available for passed in node.
+
+        :param node: name of the node to query, ''str''
+        :raises: :exc:`ROSTopicException` If topic type cannot be determined or loaded
+        """
+        self._current_loggers = []
+        self._current_levels = {}
+        # Construct the service name, taking into account our namespace
+        servicename = rosgraph.names.ns_join(
+            rosgraph.names.ns_join(rosgraph.names.get_ros_namespace(), node),
+            'get_loggers')
+        # Construct the service name, taking into account our namespace
+        servicename = rosgraph.names.resolve_name(
+            servicename, rosgraph.names.get_ros_namespace())
+        try:
+            service = rosservice.get_service_class_by_name(servicename)
+        except rosservice.ROSServiceException as e:
+            raise ROSConsoleException(
+                "node '%s' doesn't exist or doesn't support query: %s" % (node, e))
+
+        request = service._request_class()
+        proxy = rospy.ServiceProxy(str(servicename), service)
+        try:
+            response = proxy(request)
+        except rospy.ServiceException as e:
+            raise ROSConsoleException("node '%s' logger request failed: %s" % (node, e))
+
+        if response._slot_types[0] == 'roscpp/Logger[]':
+            for logger in getattr(response, response.__slots__[0]):
+                self._current_loggers.append(logger.name)
+                self._current_levels[logger.name] = logger.level
+        else:
+            raise ROSConsoleException(repr(response))
+
+    def send_logger_change_message(self, node, logger, level):
+        """
+        Send a logger level change request to 'node'.
+
+        :param node: name of the node to chaange, ''str''
+        :param logger: name of the logger to change, ''str''
+        :param level: name of the level to change, ''str''
+        :returns: True if the response is valid, ''bool''
+        :returns: False if the request raises an exception or would not change the state, ''bool''
+        """
+        # Construct the service name, taking into account our namespace
+        servicename = rosgraph.names.ns_join(
+            rosgraph.names.ns_join(rosgraph.names.get_ros_namespace(), node),
+            'set_logger_level')
+        # Construct the service name, taking into account our namespace
+        servicename = rosgraph.names.resolve_name(
+            servicename, rosgraph.names.get_ros_namespace())
+        if self._current_levels[logger] == level:
+            return False
+
+        service = rosservice.get_service_class_by_name(servicename)
+        request = service._request_class()
+        request.logger = logger
+        request.level = level
+        proxy = rospy.ServiceProxy(str(servicename), service)
+        try:
+            proxy(request)
+            self._current_levels[logger] = level.upper()
+        except rospy.ServiceException as e:
+            raise ROSConsoleException("node '%s' logger request failed: %s" % (node, e))
+
+        return True
diff --git a/clients/rospy/src/rospy/msg.py b/clients/rospy/src/rospy/msg.py
index e87b47f..c7fd800 100644
--- a/clients/rospy/src/rospy/msg.py
+++ b/clients/rospy/src/rospy/msg.py
@@ -114,12 +114,12 @@ def args_kwds_to_message(data_class, args, kwds):
             # data_class has fields and that the type matches.  This
             # branch isn't necessary but provides more useful
             # information to users
-            elif isinstance(arg, genpy.Message) and \
-                    (len(data_class._slot_types) == 0 or \
-                         arg._type != data_class._slot_types[0]):
-                raise TypeError("expected [%s] but got [%s]"%(data_class._slot_types[0], arg._type))
-            else:
-                return data_class(*args)
+            elif isinstance(arg, genpy.Message):
+                if len(data_class._slot_types) == 0:
+                    raise TypeError("expected [] but got [%s]"%arg._type)
+                elif arg._type != data_class._slot_types[0]:
+                    raise TypeError("expected [%s] but got [%s]"%(data_class._slot_types[0], arg._type))
+            return data_class(*args)
         else:
             return data_class(*args)
 
diff --git a/clients/rospy/src/rospy/rosconsole.py b/clients/rospy/src/rospy/rosconsole.py
new file mode 100644
index 0000000..1795ee3
--- /dev/null
+++ b/clients/rospy/src/rospy/rosconsole.py
@@ -0,0 +1,183 @@
+# Software License Agreement (BSD License)
+#
+# Copyright (c) 2015, Chris Mansley, Open Source Robotics Foundation, 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.
+
+from __future__ import print_function
+
+import os
+import socket
+import sys
+
+import rosgraph
+import rospy
+
+from .logger_level_service_caller import LoggerLevelServiceCaller
+from .logger_level_service_caller import ROSConsoleException
+
+NAME = 'rosconsole'
+
+
+def error(status, msg):
+    print("%s: error: %s" % (NAME, msg), file=sys.stderr)
+    sys.exit(status)
+
+
+def _get_cmd_list_optparse():
+    from optparse import OptionParser
+
+    usage = "usage: %prog list <node>"
+    parser = OptionParser(usage=usage, prog=NAME)
+
+    return parser
+
+
+def _rosconsole_cmd_list(argv):
+    args = argv[2:]
+    parser = _get_cmd_list_optparse()
+    (options, args) = parser.parse_args(args)
+
+    if not args:
+        parser.error("you must specify a node to list loggers")
+    elif len(args) > 1:
+        parser.error("you may only specify one node to list")
+
+    logger_level = LoggerLevelServiceCaller()
+
+    loggers = logger_level.get_loggers(args[0])
+
+    output = '\n'.join(loggers)
+    print(output)
+
+
+def _get_cmd_set_optparse():
+    from optparse import OptionParser
+
+    usage = "usage: %prog set <node> <logger> <level>"
+    levels = ', '.join(LoggerLevelServiceCaller().get_levels())
+    usage += "\n\n <level> must be one of [" + levels + "]"
+    parser = OptionParser(usage=usage, prog=NAME)
+
+    return parser
+
+
+def _rosconsole_cmd_set(argv):
+    args = argv[2:]
+    parser = _get_cmd_set_optparse()
+    (options, args) = parser.parse_args(args)
+
+    if len(args) < 3:
+        parser.error("you must specify a node, a logger and a level")
+
+    logger_level = LoggerLevelServiceCaller()
+
+    if args[1] not in logger_level._current_levels:
+        error(2, "node " + args[0] + " does not contain logger " + args[1])
+
+    level = args[2].lower()
+    if level not in logger_level.get_levels():
+        parser.error("invalid level")
+
+    logger_level.send_logger_change_message(args[0], args[1], args[2])
+
+
+def _get_cmd_get_optparse():
+    from optparse import OptionParser
+
+    usage = "usage: %prog get <node> <logger>"
+    parser = OptionParser(usage=usage, prog=NAME)
+
+    return parser
+
+
+def _rosconsole_cmd_get(argv):
+    args = argv[2:]
+    parser = _get_cmd_get_optparse()
+    (options, args) = parser.parse_args(args)
+
+    if len(args) < 2:
+        parser.error("you must specify a node and a logger")
+
+    logger_level = LoggerLevelServiceCaller()
+
+    if args[1] not in logger_level._current_levels:
+        error(2, "node " + args[0] + " does not contain logger " + args[1])
+
+    print(logger_level._current_levels[args[1]])
+
+
+def _fullusage():
+    print("""rosconsole is a command-line tool for configuring the logger level of ROS nodes.
+
+Commands:
+\trosconsole get\tdisplay level for a logger
+\trosconsole list\tlist loggers for a node
+\trosconsole set\tset level for a logger
+
+Type rosconsole <command> -h for more detailed usage, e.g. 'rosconsole list -h'
+""")
+    sys.exit(getattr(os, 'EX_USAGE', 1))
+
+
+def main(argv=None):
+    if argv is None:
+        argv = sys.argv
+
+    # Initialize ourselves as a node, to ensure handling of namespace and
+    # remapping arguments
+    rospy.init_node('rosconsole', anonymous=True)
+    argv = rospy.myargv(argv)
+
+    # process argv
+    if len(argv) == 1:
+        _fullusage()
+
+    try:
+        command = argv[1]
+        if command == 'get':
+            _rosconsole_cmd_get(argv)
+        elif command == 'list':
+            _rosconsole_cmd_list(argv)
+        elif command == 'set':
+            _rosconsole_cmd_set(argv)
+        else:
+            _fullusage()
+    except socket.error as e:
+        error(1,
+              "Network communication failed; most likely failed to communicate with master: %s" % e)
+    except rosgraph.MasterException as e:
+        # mainly for invalid master URI/rosgraph.masterapi
+        error(1, str(e))
+    except ROSConsoleException as e:
+        error(1, str(e))
+    except KeyboardInterrupt:
+        pass
+    except rospy.ROSInterruptException:
+        pass
diff --git a/clients/rospy/src/rospy/timer.py b/clients/rospy/src/rospy/timer.py
index f82de5f..e0197f6 100644
--- a/clients/rospy/src/rospy/timer.py
+++ b/clients/rospy/src/rospy/timer.py
@@ -59,6 +59,31 @@ class Rate(object):
         self.last_time = rospy.rostime.get_rostime()
         self.sleep_dur = rospy.rostime.Duration(0, int(1e9/hz))
 
+    def _remaining(self, curr_time):
+        """
+        Calculate the time remaining for rate to sleep.
+        @param curr_time: current time
+        @type  curr_time: L{Time}
+        @return: time remaining
+        @rtype: L{Time}
+        """
+        # detect time jumping backwards
+        if self.last_time > curr_time:
+            self.last_time = curr_time
+
+        # calculate remaining time
+        elapsed = curr_time - self.last_time
+        return self.sleep_dur - elapsed
+
+    def remaining(self):
+        """
+        Return the time remaining for rate to sleep.
+        @return: time remaining
+        @rtype: L{Time}
+        """
+        curr_time = rospy.rostime.get_rostime()
+        return self._remaining(curr_time)
+
     def sleep(self):
         """
         Attempt sleep at the specified rate. sleep() takes into
@@ -71,13 +96,7 @@ class Rate(object):
         backwards
         """
         curr_time = rospy.rostime.get_rostime()
-        # detect time jumping backwards
-        if self.last_time > curr_time:
-            self.last_time = curr_time
-
-        # calculate sleep interval
-        elapsed = curr_time - self.last_time
-        sleep(self.sleep_dur - elapsed)
+        sleep(self._remaining(curr_time))
         self.last_time = self.last_time + self.sleep_dur
 
         # detect time jumping forwards, as well as loops that are
diff --git a/clients/rospy/src/rospy/topics.py b/clients/rospy/src/rospy/topics.py
index d3a5246..ca8e44e 100644
--- a/clients/rospy/src/rospy/topics.py
+++ b/clients/rospy/src/rospy/topics.py
@@ -374,6 +374,15 @@ class _TopicImpl(object):
         """
         rospyinfo("topic[%s] adding connection to [%s], count %s"%(self.resolved_name, c.endpoint_id, len(self.connections)))
         with self.c_lock:
+            # protect against race condition adding connection to closed sub
+            if self.closed:
+                rospyerr(
+                    "ERROR: Race condition failure adding connection to closed subscriber\n"
+                    "If you run into this please comment on "
+                    "https://github.com/ros/ros_comm/issues/544"
+                )
+                return False
+
             # c_lock is to make add_connection thread-safe, but we
             # still make a copy of self.connections so that the rest of the
             # code can use self.connections in an unlocked manner
diff --git a/ros_comm/CHANGELOG.rst b/ros_comm/CHANGELOG.rst
index 6ae895a..a1f3484 100644
--- a/ros_comm/CHANGELOG.rst
+++ b/ros_comm/CHANGELOG.rst
@@ -2,6 +2,9 @@
 Changelog for package ros_comm
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.11.11 (2015-04-16)
+--------------------
+
 1.11.10 (2014-12-22)
 --------------------
 
diff --git a/ros_comm/package.xml b/ros_comm/package.xml
index 02b09bd..141e668 100644
--- a/ros_comm/package.xml
+++ b/ros_comm/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>ros_comm</name>
-  <version>1.11.10</version>
+  <version>1.11.11</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/package.xml b/test/test_rosbag/package.xml
index 36c9a24..5ecd63c 100644
--- a/test/test_rosbag/package.xml
+++ b/test/test_rosbag/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>test_rosbag</name>
-  <version>1.11.10</version>
+  <version>1.11.11</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 2116e1c..913a985 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.11.10</version>
+  <version>1.11.11</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 bb2c14a..d2bfd2a 100644
--- a/test/test_roscpp/package.xml
+++ b/test/test_roscpp/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>test_roscpp</name>
-  <version>1.11.10</version>
+  <version>1.11.11</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 74138a2..53081fa 100644
--- a/test/test_roscpp/test/CMakeLists.txt
+++ b/test/test_roscpp/test/CMakeLists.txt
@@ -158,3 +158,5 @@ add_rostest(launch/local_remappings.xml)
 add_rostest(launch/global_remappings.xml)
 add_rostest(launch/ns_node_remapping.xml)
 add_rostest(launch/search_param.xml)
+
+add_rostest(launch/stamped_topic_statistics_with_empty_timestamp.xml)
diff --git a/test/test_roscpp/test/launch/stamped_topic_statistics_with_empty_timestamp.xml b/test/test_roscpp/test/launch/stamped_topic_statistics_with_empty_timestamp.xml
new file mode 100644
index 0000000..0f1cbf4
--- /dev/null
+++ b/test/test_roscpp/test/launch/stamped_topic_statistics_with_empty_timestamp.xml
@@ -0,0 +1,5 @@
+<launch>
+  <param name="enable_statistics" value="true" />
+  <test test-name="stamped_topic_statistics_with_empty_timestamp" pkg="test_roscpp" type="test_roscpp-stamped_topic_statistics_empty_timestamp"/>
+</launch>
+
diff --git a/test/test_roscpp/test/src/CMakeLists.txt b/test/test_roscpp/test/src/CMakeLists.txt
index 73ccf2f..52100ee 100644
--- a/test/test_roscpp/test/src/CMakeLists.txt
+++ b/test/test_roscpp/test/src/CMakeLists.txt
@@ -198,6 +198,9 @@ add_executable(${PROJECT_NAME}-string_msg_expect EXCLUDE_FROM_ALL string_msg_exp
 target_link_libraries(${PROJECT_NAME}-string_msg_expect ${GTEST_LIBRARIES} ${catkin_LIBRARIES})
 add_dependencies(${PROJECT_NAME}-string_msg_expect std_msgs_gencpp)
 
+add_executable(${PROJECT_NAME}-stamped_topic_statistics_empty_timestamp EXCLUDE_FROM_ALL stamped_topic_statistics_empty_timestamp.cpp)
+target_link_libraries(${PROJECT_NAME}-stamped_topic_statistics_empty_timestamp ${GTEST_LIBRARIES} ${catkin_LIBRARIES})
+
 # The publisher and subscriber are compiled but not registered as a unit test
 # since the test execution requires a network connection which drops packages.
 # Call scripts/test_udp_with_dropped_packets.sh to run the test.
@@ -272,6 +275,7 @@ if(TARGET tests)
     ${PROJECT_NAME}-string_msg_expect
     ${PROJECT_NAME}-publisher
     ${PROJECT_NAME}-subscriber
+    ${PROJECT_NAME}-stamped_topic_statistics_empty_timestamp
   )
 endif()
 
@@ -334,3 +338,5 @@ add_dependencies(${PROJECT_NAME}-test_ns_node_remapping ${PROJECT_NAME}_gencpp)
 add_dependencies(${PROJECT_NAME}-test_search_param ${PROJECT_NAME}_gencpp)
 add_dependencies(${PROJECT_NAME}-left_right ${PROJECT_NAME}_gencpp)
 add_dependencies(${PROJECT_NAME}-string_msg_expect ${PROJECT_NAME}_gencpp)
+add_dependencies(${PROJECT_NAME}-stamped_topic_statistics_empty_timestamp
+ ${PROJECT_NAME}_gencpp)
diff --git a/test/test_roscpp/test/src/params.cpp b/test/test_roscpp/test/src/params.cpp
index 206969e..39df6ba 100644
--- a/test/test_roscpp/test/src/params.cpp
+++ b/test/test_roscpp/test/src/params.cpp
@@ -528,6 +528,38 @@ TEST(Params, mapBoolParam)
   ASSERT_TRUE(std::equal(map_b.begin(), map_b.end(), map_b2.begin()));
 }
 
+TEST(Params, paramTemplateFunction)
+{
+  EXPECT_EQ( param::param<std::string>( "string", "" ), "test" );
+  EXPECT_EQ( param::param<std::string>( "gnirts", "test" ), "test" );
+
+  EXPECT_EQ( param::param<int>( "int", 0 ), 10 );
+  EXPECT_EQ( param::param<int>( "tni", 10 ), 10 );
+
+  EXPECT_DOUBLE_EQ( param::param<double>( "double", 0.0 ), 10.5 );
+  EXPECT_DOUBLE_EQ( param::param<double>( "elbuod", 10.5 ), 10.5 );
+
+  EXPECT_EQ( param::param<bool>( "bool", true ), false );
+  EXPECT_EQ( param::param<bool>( "loob", true ), true );
+}
+
+TEST(Params, paramNodeHandleTemplateFunction)
+{
+  NodeHandle nh;
+
+  EXPECT_EQ( nh.param<std::string>( "string", "" ), "test" );
+  EXPECT_EQ( nh.param<std::string>( "gnirts", "test" ), "test" );
+
+  EXPECT_EQ( nh.param<int>( "int", 0 ), 10 );
+  EXPECT_EQ( nh.param<int>( "tni", 10 ), 10 );
+
+  EXPECT_DOUBLE_EQ( nh.param<double>( "double", 0.0 ), 10.5 );
+  EXPECT_DOUBLE_EQ( nh.param<double>( "elbuod", 10.5 ), 10.5 );
+
+  EXPECT_EQ( nh.param<bool>( "bool", true ), false );
+  EXPECT_EQ( nh.param<bool>( "loob", true ), true );
+}
+
 int
 main(int argc, char** argv)
 {
diff --git a/test/test_roscpp/test/src/stamped_topic_statistics_empty_timestamp.cpp b/test/test_roscpp/test/src/stamped_topic_statistics_empty_timestamp.cpp
new file mode 100644
index 0000000..a8bf089
--- /dev/null
+++ b/test/test_roscpp/test/src/stamped_topic_statistics_empty_timestamp.cpp
@@ -0,0 +1,71 @@
+/*
+ * Copyright (c) 2015, Eric Perko
+ * 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 copyright holder nor the names of its
+ *       contributors may be used to endorse or promote products derived from
+ *       this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#include <gtest/gtest.h>
+
+#include <ros/ros.h>
+
+#include <test_roscpp/TestWithHeader.h>
+
+void callback(const test_roscpp::TestWithHeaderConstPtr& msg)
+{
+  // No operation needed here
+}
+
+TEST(TopicStatistics, empty_timestamp_crash_check)
+{
+  ros::NodeHandle nh;
+
+  ros::Publisher pub = nh.advertise<test_roscpp::TestWithHeader>("test_with_empty_timestamp", 0);
+  ros::Subscriber sub = nh.subscribe("test_with_empty_timestamp", 0, callback);
+
+  ros::Time start = ros::Time::now();
+  ros::Duration time_to_publish(10.0);
+  while ( (ros::Time::now() - start) < time_to_publish )
+  {
+    test_roscpp::TestWithHeader msg;
+    msg.header.frame_id = "foo";
+    // Don't fill in timestamp so that it defaults to 0.0
+
+    pub.publish(msg);
+    ros::spinOnce();
+    ros::WallDuration(0.01).sleep();
+  }
+
+  SUCCEED();
+}
+
+int main(int argc, char **argv)
+{
+  testing::InitGoogleTest(&argc, argv);
+
+  ros::init(argc, argv, "stamped_topic_statistics_empty_timestamp");
+
+  return RUN_ALL_TESTS();
+}
\ No newline at end of file
diff --git a/test/test_rosgraph/package.xml b/test/test_rosgraph/package.xml
index 818d2a6..31a8933 100644
--- a/test/test_rosgraph/package.xml
+++ b/test/test_rosgraph/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>test_rosgraph</name>
-  <version>1.11.10</version>
+  <version>1.11.11</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 08733f3..ba3b2d5 100644
--- a/test/test_roslaunch/package.xml
+++ b/test/test_roslaunch/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>test_roslaunch</name>
-  <version>1.11.10</version>
+  <version>1.11.11</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 c985555..a552f64 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.11.10</version>
+  <version>1.11.11</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 b1dc3b3..75d776d 100644
--- a/test/test_rosmaster/package.xml
+++ b/test/test_rosmaster/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>test_rosmaster</name>
-  <version>1.11.10</version>
+  <version>1.11.11</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 b83ee68..2ba6892 100644
--- a/test/test_rosparam/package.xml
+++ b/test/test_rosparam/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>test_rosparam</name>
-  <version>1.11.10</version>
+  <version>1.11.11</version>
   <description>
     A package containing the unit tests for rosparam.
   </description>
diff --git a/test/test_rospy/CMakeLists.txt b/test/test_rospy/CMakeLists.txt
index a44ef95..ba7d5f5 100644
--- a/test/test_rospy/CMakeLists.txt
+++ b/test/test_rospy/CMakeLists.txt
@@ -9,6 +9,7 @@ if(CATKIN_ENABLE_TESTING)
     FILES
     ArrayVal.msg
     EmbedTest.msg
+    Empty.msg
     Floats.msg
     HeaderHeaderVal.msg
     HeaderVal.msg
diff --git a/test/test_rospy/msg/Empty.msg b/test/test_rospy/msg/Empty.msg
new file mode 100644
index 0000000..e69de29
diff --git a/test/test_rospy/package.xml b/test/test_rospy/package.xml
index afd7dcd..fc72192 100644
--- a/test/test_rospy/package.xml
+++ b/test/test_rospy/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>test_rospy</name>
-  <version>1.11.10</version>
+  <version>1.11.11</version>
   <description>
     rospy unit and integration test framework.
   </description>
diff --git a/test/test_rospy/test/unit/test_rospy_msg.py b/test/test_rospy/test/unit/test_rospy_msg.py
index 1129bc6..47508d0 100644
--- a/test/test_rospy/test/unit/test_rospy_msg.py
+++ b/test/test_rospy/test/unit/test_rospy_msg.py
@@ -49,7 +49,7 @@ class TestRospyMsg(unittest.TestCase):
     def test_args_kwds_to_message(self):
         import rospy
         from rospy.msg import args_kwds_to_message
-        from test_rospy.msg import Val
+        from test_rospy.msg import Val, Empty
         
         v = Val('hello world-1')
         d = args_kwds_to_message(Val, (v,), None)
@@ -64,6 +64,10 @@ class TestRospyMsg(unittest.TestCase):
             args_kwds_to_message(Val, 'hi', val='hello world-3')
             self.fail("should not allow args and kwds")
         except TypeError: pass
+        try:
+            args_kwds_to_message(Empty, (Val('hola'),), None)
+            self.fail("should raise TypeError when publishing Val msg to Empty topic")
+        except TypeError: pass
 
     def test_serialize_message(self):
         import rospy.msg
diff --git a/test/test_rosservice/package.xml b/test/test_rosservice/package.xml
index f457cd0..74923ac 100644
--- a/test/test_rosservice/package.xml
+++ b/test/test_rosservice/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>test_rosservice</name>
-  <version>1.11.10</version>
+  <version>1.11.11</version>
   <description>
     Tests for the rosservice tool.
   </description>
diff --git a/tools/rosbag/CHANGELOG.rst b/tools/rosbag/CHANGELOG.rst
index 0577fa3..67cafbd 100644
--- a/tools/rosbag/CHANGELOG.rst
+++ b/tools/rosbag/CHANGELOG.rst
@@ -2,6 +2,10 @@
 Changelog for package rosbag
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.11.11 (2015-04-16)
+--------------------
+* add support for pausing when specified topics are about to be published (`#569 <https://github.com/ros/ros_comm/pull/569>`_)
+
 1.11.10 (2014-12-22)
 --------------------
 * add option to specify the minimum disk space at which recording is stopped (`#500 <https://github.com/ros/ros_comm/pull/500>`_)
diff --git a/tools/rosbag/include/rosbag/player.h b/tools/rosbag/include/rosbag/player.h
index e7efbc1..19c777f 100644
--- a/tools/rosbag/include/rosbag/player.h
+++ b/tools/rosbag/include/rosbag/player.h
@@ -90,6 +90,7 @@ struct ROSBAG_DECL PlayerOptions
 
     std::vector<std::string> bags;
     std::vector<std::string> topics;
+    std::vector<std::string> pause_topics;
 };
 
 
@@ -183,6 +184,8 @@ private:
 
     bool paused_;
 
+    bool pause_for_topics_;
+
     ros::WallTime paused_time_;
 
     std::vector<boost::shared_ptr<Bag> >  bags_;
diff --git a/tools/rosbag/package.xml b/tools/rosbag/package.xml
index 67b86d3..9f060b8 100644
--- a/tools/rosbag/package.xml
+++ b/tools/rosbag/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>rosbag</name>
-  <version>1.11.10</version>
+  <version>1.11.11</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/play.cpp b/tools/rosbag/src/play.cpp
index ffb8873..4726e75 100644
--- a/tools/rosbag/src/play.cpp
+++ b/tools/rosbag/src/play.cpp
@@ -59,6 +59,7 @@ rosbag::PlayerOptions parseOptions(int argc, char** argv) {
       ("keep-alive,k", "keep alive past end of bag (useful for publishing latched topics)")
       ("try-future-version", "still try to open a bag file, even if the version is not known to the player")
       ("topics", po::value< std::vector<std::string> >()->multitoken(), "topics to play back")
+      ("pause-topics", po::value< std::vector<std::string> >()->multitoken(), "topics to pause playback on")
       ("bags", po::value< std::vector<std::string> >(), "bag files to play back from");
     
     po::positional_options_description p;
@@ -124,6 +125,15 @@ rosbag::PlayerOptions parseOptions(int argc, char** argv) {
         opts.topics.push_back(*i);
     }
 
+    if (vm.count("pause-topics"))
+    {
+      std::vector<std::string> pause_topics = vm["pause-topics"].as< std::vector<std::string> >();
+      for (std::vector<std::string>::iterator i = pause_topics.begin();
+           i != pause_topics.end();
+           i++)
+        opts.pause_topics.push_back(*i);
+    }
+
     if (vm.count("bags"))
     {
       std::vector<std::string> bags = vm["bags"].as< std::vector<std::string> >();
@@ -132,8 +142,9 @@ rosbag::PlayerOptions parseOptions(int argc, char** argv) {
            i++)
           opts.bags.push_back(*i);
     } else {
-      if (vm.count("topics"))
-        throw ros::Exception("When using --topics, --bags should be specified to list bags.");
+      if (vm.count("topics") || vm.count("pause-topics"))
+        throw ros::Exception("When using --topics or --pause-topics, --bags "
+          "should be specified to list bags.");
       throw ros::Exception("You must specify at least one bag to play back.");
     }
             
diff --git a/tools/rosbag/src/player.cpp b/tools/rosbag/src/player.cpp
index 1944000..cf76a6d 100644
--- a/tools/rosbag/src/player.cpp
+++ b/tools/rosbag/src/player.cpp
@@ -102,7 +102,10 @@ void PlayerOptions::check() {
 Player::Player(PlayerOptions const& options) :
     options_(options),
     paused_(false),
-    terminal_modified_(false)
+    terminal_modified_(false),
+    // If we were given a list of topics to pause on, then go into that mode
+    // by default (it can be toggled later via 't' from the keyboard).
+    pause_for_topics_(options_.pause_topics.size() > 0)
 {
 }
 
@@ -307,6 +310,20 @@ void Player::doPublish(MessageInstance const& m) {
       return;
     }
 
+    if (pause_for_topics_)
+    {
+        for (std::vector<std::string>::iterator i = options_.pause_topics.begin();
+             i != options_.pause_topics.end();
+             ++i)
+        {
+            if (topic == *i)
+            {
+                paused_ = true;
+                paused_time_ = ros::WallTime::now();
+            }
+        }
+    }
+
     while ((paused_ || !time_publisher_.horizonReached()) && node_handle_.ok())
     {
         bool charsleftorpaused = true;
@@ -347,6 +364,9 @@ void Player::doPublish(MessageInstance const& m) {
                     return;
                 }
                 break;
+            case 't':
+                pause_for_topics_ = !pause_for_topics_;
+                break;
             case EOF:
                 if (paused_)
                 {
@@ -492,7 +512,7 @@ int Player::readCharFromStdin() {
         b = ReadConsoleInput(input_handle, input_record, input_size, &events);
         if (b)
         {
-            for (unsigned int i = 0; i < events; i++)
+            for (unsigned int i = 0; i < events; ++i)
             {
                 if (input_record[i].EventType & KEY_EVENT & input_record[i].Event.KeyEvent.bKeyDown)
                 {
diff --git a/tools/rosbag/src/rosbag/rosbag_main.py b/tools/rosbag/src/rosbag/rosbag_main.py
index ad51888..15cb3ce 100644
--- a/tools/rosbag/src/rosbag/rosbag_main.py
+++ b/tools/rosbag/src/rosbag/rosbag_main.py
@@ -172,6 +172,18 @@ def handle_topics(option, opt_str, value, parser):
     del parser.rargs[:len(topics)]
 
 
+def handle_pause_topics(option, opt_str, value, parser):
+    pause_topics = []
+    for arg in parser.rargs:
+        if arg[:2] == "--" and len(arg) > 2:
+            break
+        if arg[:1] == "-" and len(arg) > 1:
+            break
+        pause_topics.append(arg)
+    parser.values.pause_topics.extend(pause_topics)
+    del parser.rargs[:len(pause_topics)]
+
+
 def play_cmd(argv):
     parser = optparse.OptionParser(usage="rosbag play BAGFILE1 [BAGFILE2 BAGFILE3 ...]",
                                    description="Play back the contents of one or more bag files in a time-synchronized fashion.")
@@ -190,6 +202,7 @@ def play_cmd(argv):
     parser.add_option("-k", "--keep-alive",   dest="keep_alive", default=False, action="store_true", help="keep alive past end of bag (useful for publishing latched topics)")
     parser.add_option("--try-future-version", dest="try_future", default=False, action="store_true", help="still try to open a bag file, even if the version number is not known to the player")
     parser.add_option("--topics", dest="topics", default=[],  callback=handle_topics, action="callback", help="topics to play back")
+    parser.add_option("--pause-topics", dest="pause_topics", default=[],  callback=handle_pause_topics, action="callback", help="topics to pause on during playback")
     parser.add_option("--bags",  help="bags files to play back from")
 
     (options, args) = parser.parse_args(argv)
@@ -222,7 +235,13 @@ def play_cmd(argv):
         cmd.extend(['--skip-empty', str(options.skip_empty)])
 
     if options.topics:
-        cmd.extend(['--topics'] + options.topics + ['--bags'])
+        cmd.extend(['--topics'] + options.topics)
+
+    if options.pause_topics:
+        cmd.extend(['--pause-topics'] + options.pause_topics)
+
+    if options.bags:
+        cmd.extend(["--bags", str(options.bags)])
 
     cmd.extend(args)
     # Better way of handling it than os.execv
diff --git a/tools/rosbag_storage/CHANGELOG.rst b/tools/rosbag_storage/CHANGELOG.rst
index 69f1e76..8e36bd4 100644
--- a/tools/rosbag_storage/CHANGELOG.rst
+++ b/tools/rosbag_storage/CHANGELOG.rst
@@ -2,6 +2,10 @@
 Changelog for package rosbag_storage
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.11.11 (2015-04-16)
+--------------------
+* support large bagfiles (>2GB) on 32-bit systems (`#464 <https://github.com/ros/ros_comm/issues/464>`_)
+
 1.11.10 (2014-12-22)
 --------------------
 * fix various defects reported by coverity
diff --git a/tools/rosbag_storage/CMakeLists.txt b/tools/rosbag_storage/CMakeLists.txt
index 7c0679b..4ceee01 100644
--- a/tools/rosbag_storage/CMakeLists.txt
+++ b/tools/rosbag_storage/CMakeLists.txt
@@ -14,6 +14,9 @@ catkin_package(
   DEPENDS console_bridge Boost
 )
 
+# Support large bags (>2GB) on 32-bit systems
+add_definitions(-D_FILE_OFFSET_BITS=64)
+
 include_directories(include ${catkin_INCLUDE_DIRS} ${console_bridge_INCLUDE_DIRS} ${Boost_INCLUDE_DIRS} ${BZIP2_INCLUDE_DIR})
 add_definitions(${BZIP2_DEFINITIONS})
 
diff --git a/tools/rosbag_storage/package.xml b/tools/rosbag_storage/package.xml
index 9300a0b..cf68ea9 100644
--- a/tools/rosbag_storage/package.xml
+++ b/tools/rosbag_storage/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>rosbag_storage</name>
-  <version>1.11.10</version>
+  <version>1.11.11</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 4b45f46..5c43acb 100644
--- a/tools/rosconsole/CHANGELOG.rst
+++ b/tools/rosconsole/CHANGELOG.rst
@@ -2,6 +2,10 @@
 Changelog for package rosconsole
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.11.11 (2015-04-16)
+--------------------
+* add DELAYED_THROTTLE versions of log macros (`#571 <https://github.com/ros/ros_comm/issues/571>`_)
+
 1.11.10 (2014-12-22)
 --------------------
 * fix various defects reported by coverity
diff --git a/tools/rosconsole/include/ros/console.h b/tools/rosconsole/include/ros/console.h
index 98ca867..793e64d 100644
--- a/tools/rosconsole/include/ros/console.h
+++ b/tools/rosconsole/include/ros/console.h
@@ -474,6 +474,47 @@ ROSCONSOLE_DECL std::string formatToString(const char* fmt, ...);
   } while(0)
 
 /**
+ * \brief Log to a given named logger at a given verbosity level, limited to a specific rate of printing, with printf-style formatting
+ *
+ * \param level One of the levels specified in ::ros::console::levels::Level
+ * \param name Name of the logger.  Note that this is the fully qualified name, and does NOT include "ros.<package_name>".  Use ROSCONSOLE_DEFAULT_NAME if you would like to use the default name.
+ * \param rate The rate it should actually trigger at
+ */
+#define ROS_LOG_DELAYED_THROTTLE(rate, level, name, ...) \
+  do \
+  { \
+    ROSCONSOLE_DEFINE_LOCATION(true, level, name); \
+    ::ros::Time __ros_log_delayed_throttle__now__ = ::ros::Time::now(); \
+    static double __ros_log_delayed_throttle__last_hit__ = __ros_log_delayed_throttle__now__.toSec(); \
+    if (ROS_UNLIKELY(__rosconsole_define_location__enabled) && ROS_UNLIKELY(__ros_log_delayed_throttle__last_hit__ + rate <= __ros_log_delayed_throttle__now__.toSec())) \
+    { \
+      __ros_log_delayed_throttle__last_hit__ = __ros_log_delayed_throttle__now__.toSec(); \
+      ROSCONSOLE_PRINT_AT_LOCATION(__VA_ARGS__); \
+    } \
+  } while(0)
+
+// inside a macro which uses args use only well namespaced variable names in order to not overlay variables coming in via args
+/**
+ * \brief Log to a given named logger at a given verbosity level, limited to a specific rate of printing and postponed first message
+ *
+ * \param level One of the levels specified in ::ros::console::levels::Level
+ * \param name Name of the logger.  Note that this is the fully qualified name, and does NOT include "ros.<package_name>".  Use ROSCONSOLE_DEFAULT_NAME if you would like to use the default name.
+ * \param rate The rate it should actually trigger at, and the delay before which no message will be shown.
+ */
+#define ROS_LOG_STREAM_DELAYED_THROTTLE(rate, level, name, args) \
+  do \
+  { \
+    ROSCONSOLE_DEFINE_LOCATION(true, level, name); \
+    ::ros::Time __ros_log_stream_delayed_throttle__now__ = ::ros::Time::now(); \
+    static double __ros_log_stream_delayed_throttle__last_hit__ = __ros_log_stream_delayed_throttle__now__.toSec(); \
+    if (ROS_UNLIKELY(__rosconsole_define_location__enabled) && ROS_UNLIKELY(__ros_log_stream_delayed_throttle__last_hit__ + rate <= __ros_log_stream_delayed_throttle__now__.toSec())) \
+    { \
+      __ros_log_stream_delayed_throttle__last_hit__ = __ros_log_stream_delayed_throttle__now__.toSec(); \
+      ROSCONSOLE_PRINT_STREAM_AT_LOCATION(args); \
+    } \
+  } while(0)
+
+/**
  * \brief Log to a given named logger at a given verbosity level, with user-defined filtering, with printf-style formatting
  *
  * \param filter pointer to the filter to be used
diff --git a/tools/rosconsole/include/rosconsole/macros_generated.h b/tools/rosconsole/include/rosconsole/macros_generated.h
index 0eb2c46..fc24951 100644
--- a/tools/rosconsole/include/rosconsole/macros_generated.h
+++ b/tools/rosconsole/include/rosconsole/macros_generated.h
@@ -46,6 +46,10 @@
 #define ROS_DEBUG_STREAM_THROTTLE(rate, args)
 #define ROS_DEBUG_THROTTLE_NAMED(rate, name, ...)
 #define ROS_DEBUG_STREAM_THROTTLE_NAMED(rate, name, args)
+#define ROS_DEBUG_DELAYED_THROTTLE(rate, ...)
+#define ROS_DEBUG_STREAM_DELAYED_THROTTLE(rate, args)
+#define ROS_DEBUG_DELAYED_THROTTLE_NAMED(rate, name, ...)
+#define ROS_DEBUG_STREAM_DELAYED_THROTTLE_NAMED(rate, name, args)
 #define ROS_DEBUG_FILTER(filter, ...)
 #define ROS_DEBUG_STREAM_FILTER(filter, args)
 #define ROS_DEBUG_FILTER_NAMED(filter, name, ...)
@@ -67,6 +71,10 @@
 #define ROS_DEBUG_STREAM_THROTTLE(rate, args) ROS_LOG_STREAM_THROTTLE(rate, ::ros::console::levels::Debug, ROSCONSOLE_DEFAULT_NAME, args)
 #define ROS_DEBUG_THROTTLE_NAMED(rate, name, ...) ROS_LOG_THROTTLE(rate, ::ros::console::levels::Debug, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, __VA_ARGS__)
 #define ROS_DEBUG_STREAM_THROTTLE_NAMED(rate, name, args) ROS_LOG_STREAM_THROTTLE(rate, ::ros::console::levels::Debug, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, args)
+#define ROS_DEBUG_DELAYED_THROTTLE(rate, ...) ROS_LOG_DELAYED_THROTTLE(rate, ::ros::console::levels::Debug, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__)
+#define ROS_DEBUG_STREAM_DELAYED_THROTTLE(rate, args) ROS_LOG_STREAM_DELAYED_THROTTLE(rate, ::ros::console::levels::Debug, ROSCONSOLE_DEFAULT_NAME, args)
+#define ROS_DEBUG_DELAYED_THROTTLE_NAMED(rate, name, ...) ROS_LOG_DELAYED_THROTTLE(rate, ::ros::console::levels::Debug, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, __VA_ARGS__)
+#define ROS_DEBUG_STREAM_DELAYED_THROTTLE_NAMED(rate, name, args) ROS_LOG_STREAM_DELAYED_THROTTLE(rate, ::ros::console::levels::Debug, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, args)
 #define ROS_DEBUG_FILTER(filter, ...) ROS_LOG_FILTER(filter, ::ros::console::levels::Debug, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__)
 #define ROS_DEBUG_STREAM_FILTER(filter, args) ROS_LOG_STREAM_FILTER(filter, ::ros::console::levels::Debug, ROSCONSOLE_DEFAULT_NAME, args)
 #define ROS_DEBUG_FILTER_NAMED(filter, name, ...) ROS_LOG_FILTER(filter, ::ros::console::levels::Debug, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, __VA_ARGS__)
@@ -90,6 +98,10 @@
 #define ROS_INFO_STREAM_THROTTLE(rate, args)
 #define ROS_INFO_THROTTLE_NAMED(rate, name, ...)
 #define ROS_INFO_STREAM_THROTTLE_NAMED(rate, name, args)
+#define ROS_INFO_DELAYED_THROTTLE(rate, ...)
+#define ROS_INFO_STREAM_DELAYED_THROTTLE(rate, args)
+#define ROS_INFO_DELAYED_THROTTLE_NAMED(rate, name, ...)
+#define ROS_INFO_STREAM_DELAYED_THROTTLE_NAMED(rate, name, args)
 #define ROS_INFO_FILTER(filter, ...)
 #define ROS_INFO_STREAM_FILTER(filter, args)
 #define ROS_INFO_FILTER_NAMED(filter, name, ...)
@@ -111,6 +123,10 @@
 #define ROS_INFO_STREAM_THROTTLE(rate, args) ROS_LOG_STREAM_THROTTLE(rate, ::ros::console::levels::Info, ROSCONSOLE_DEFAULT_NAME, args)
 #define ROS_INFO_THROTTLE_NAMED(rate, name, ...) ROS_LOG_THROTTLE(rate, ::ros::console::levels::Info, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, __VA_ARGS__)
 #define ROS_INFO_STREAM_THROTTLE_NAMED(rate, name, args) ROS_LOG_STREAM_THROTTLE(rate, ::ros::console::levels::Info, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, args)
+#define ROS_INFO_DELAYED_THROTTLE(rate, ...) ROS_LOG_DELAYED_THROTTLE(rate, ::ros::console::levels::Info, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__)
+#define ROS_INFO_STREAM_DELAYED_THROTTLE(rate, args) ROS_LOG_STREAM_DELAYED_THROTTLE(rate, ::ros::console::levels::Info, ROSCONSOLE_DEFAULT_NAME, args)
+#define ROS_INFO_DELAYED_THROTTLE_NAMED(rate, name, ...) ROS_LOG_DELAYED_THROTTLE(rate, ::ros::console::levels::Info, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, __VA_ARGS__)
+#define ROS_INFO_STREAM_DELAYED_THROTTLE_NAMED(rate, name, args) ROS_LOG_STREAM_DELAYED_THROTTLE(rate, ::ros::console::levels::Info, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, args)
 #define ROS_INFO_FILTER(filter, ...) ROS_LOG_FILTER(filter, ::ros::console::levels::Info, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__)
 #define ROS_INFO_STREAM_FILTER(filter, args) ROS_LOG_STREAM_FILTER(filter, ::ros::console::levels::Info, ROSCONSOLE_DEFAULT_NAME, args)
 #define ROS_INFO_FILTER_NAMED(filter, name, ...) ROS_LOG_FILTER(filter, ::ros::console::levels::Info, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, __VA_ARGS__)
@@ -134,6 +150,10 @@
 #define ROS_WARN_STREAM_THROTTLE(rate, args)
 #define ROS_WARN_THROTTLE_NAMED(rate, name, ...)
 #define ROS_WARN_STREAM_THROTTLE_NAMED(rate, name, args)
+#define ROS_WARN_DELAYED_THROTTLE(rate, ...)
+#define ROS_WARN_STREAM_DELAYED_THROTTLE(rate, args)
+#define ROS_WARN_DELAYED_THROTTLE_NAMED(rate, name, ...)
+#define ROS_WARN_STREAM_DELAYED_THROTTLE_NAMED(rate, name, args)
 #define ROS_WARN_FILTER(filter, ...)
 #define ROS_WARN_STREAM_FILTER(filter, args)
 #define ROS_WARN_FILTER_NAMED(filter, name, ...)
@@ -155,6 +175,10 @@
 #define ROS_WARN_STREAM_THROTTLE(rate, args) ROS_LOG_STREAM_THROTTLE(rate, ::ros::console::levels::Warn, ROSCONSOLE_DEFAULT_NAME, args)
 #define ROS_WARN_THROTTLE_NAMED(rate, name, ...) ROS_LOG_THROTTLE(rate, ::ros::console::levels::Warn, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, __VA_ARGS__)
 #define ROS_WARN_STREAM_THROTTLE_NAMED(rate, name, args) ROS_LOG_STREAM_THROTTLE(rate, ::ros::console::levels::Warn, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, args)
+#define ROS_WARN_DELAYED_THROTTLE(rate, ...) ROS_LOG_DELAYED_THROTTLE(rate, ::ros::console::levels::Warn, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__)
+#define ROS_WARN_STREAM_DELAYED_THROTTLE(rate, args) ROS_LOG_STREAM_DELAYED_THROTTLE(rate, ::ros::console::levels::Warn, ROSCONSOLE_DEFAULT_NAME, args)
+#define ROS_WARN_DELAYED_THROTTLE_NAMED(rate, name, ...) ROS_LOG_DELAYED_THROTTLE(rate, ::ros::console::levels::Warn, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, __VA_ARGS__)
+#define ROS_WARN_STREAM_DELAYED_THROTTLE_NAMED(rate, name, args) ROS_LOG_STREAM_DELAYED_THROTTLE(rate, ::ros::console::levels::Warn, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, args)
 #define ROS_WARN_FILTER(filter, ...) ROS_LOG_FILTER(filter, ::ros::console::levels::Warn, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__)
 #define ROS_WARN_STREAM_FILTER(filter, args) ROS_LOG_STREAM_FILTER(filter, ::ros::console::levels::Warn, ROSCONSOLE_DEFAULT_NAME, args)
 #define ROS_WARN_FILTER_NAMED(filter, name, ...) ROS_LOG_FILTER(filter, ::ros::console::levels::Warn, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, __VA_ARGS__)
@@ -178,6 +202,10 @@
 #define ROS_ERROR_STREAM_THROTTLE(rate, args)
 #define ROS_ERROR_THROTTLE_NAMED(rate, name, ...)
 #define ROS_ERROR_STREAM_THROTTLE_NAMED(rate, name, args)
+#define ROS_ERROR_DELAYED_THROTTLE(rate, ...)
+#define ROS_ERROR_STREAM_DELAYED_THROTTLE(rate, args)
+#define ROS_ERROR_DELAYED_THROTTLE_NAMED(rate, name, ...)
+#define ROS_ERROR_STREAM_DELAYED_THROTTLE_NAMED(rate, name, args)
 #define ROS_ERROR_FILTER(filter, ...)
 #define ROS_ERROR_STREAM_FILTER(filter, args)
 #define ROS_ERROR_FILTER_NAMED(filter, name, ...)
@@ -199,6 +227,10 @@
 #define ROS_ERROR_STREAM_THROTTLE(rate, args) ROS_LOG_STREAM_THROTTLE(rate, ::ros::console::levels::Error, ROSCONSOLE_DEFAULT_NAME, args)
 #define ROS_ERROR_THROTTLE_NAMED(rate, name, ...) ROS_LOG_THROTTLE(rate, ::ros::console::levels::Error, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, __VA_ARGS__)
 #define ROS_ERROR_STREAM_THROTTLE_NAMED(rate, name, args) ROS_LOG_STREAM_THROTTLE(rate, ::ros::console::levels::Error, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, args)
+#define ROS_ERROR_DELAYED_THROTTLE(rate, ...) ROS_LOG_DELAYED_THROTTLE(rate, ::ros::console::levels::Error, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__)
+#define ROS_ERROR_STREAM_DELAYED_THROTTLE(rate, args) ROS_LOG_STREAM_DELAYED_THROTTLE(rate, ::ros::console::levels::Error, ROSCONSOLE_DEFAULT_NAME, args)
+#define ROS_ERROR_DELAYED_THROTTLE_NAMED(rate, name, ...) ROS_LOG_DELAYED_THROTTLE(rate, ::ros::console::levels::Error, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, __VA_ARGS__)
+#define ROS_ERROR_STREAM_DELAYED_THROTTLE_NAMED(rate, name, args) ROS_LOG_STREAM_DELAYED_THROTTLE(rate, ::ros::console::levels::Error, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, args)
 #define ROS_ERROR_FILTER(filter, ...) ROS_LOG_FILTER(filter, ::ros::console::levels::Error, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__)
 #define ROS_ERROR_STREAM_FILTER(filter, args) ROS_LOG_STREAM_FILTER(filter, ::ros::console::levels::Error, ROSCONSOLE_DEFAULT_NAME, args)
 #define ROS_ERROR_FILTER_NAMED(filter, name, ...) ROS_LOG_FILTER(filter, ::ros::console::levels::Error, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, __VA_ARGS__)
@@ -222,6 +254,10 @@
 #define ROS_FATAL_STREAM_THROTTLE(rate, args)
 #define ROS_FATAL_THROTTLE_NAMED(rate, name, ...)
 #define ROS_FATAL_STREAM_THROTTLE_NAMED(rate, name, args)
+#define ROS_FATAL_DELAYED_THROTTLE(rate, ...)
+#define ROS_FATAL_STREAM_DELAYED_THROTTLE(rate, args)
+#define ROS_FATAL_DELAYED_THROTTLE_NAMED(rate, name, ...)
+#define ROS_FATAL_STREAM_DELAYED_THROTTLE_NAMED(rate, name, args)
 #define ROS_FATAL_FILTER(filter, ...)
 #define ROS_FATAL_STREAM_FILTER(filter, args)
 #define ROS_FATAL_FILTER_NAMED(filter, name, ...)
@@ -243,6 +279,10 @@
 #define ROS_FATAL_STREAM_THROTTLE(rate, args) ROS_LOG_STREAM_THROTTLE(rate, ::ros::console::levels::Fatal, ROSCONSOLE_DEFAULT_NAME, args)
 #define ROS_FATAL_THROTTLE_NAMED(rate, name, ...) ROS_LOG_THROTTLE(rate, ::ros::console::levels::Fatal, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, __VA_ARGS__)
 #define ROS_FATAL_STREAM_THROTTLE_NAMED(rate, name, args) ROS_LOG_STREAM_THROTTLE(rate, ::ros::console::levels::Fatal, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, args)
+#define ROS_FATAL_DELAYED_THROTTLE(rate, ...) ROS_LOG_DELAYED_THROTTLE(rate, ::ros::console::levels::Fatal, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__)
+#define ROS_FATAL_STREAM_DELAYED_THROTTLE(rate, args) ROS_LOG_STREAM_DELAYED_THROTTLE(rate, ::ros::console::levels::Fatal, ROSCONSOLE_DEFAULT_NAME, args)
+#define ROS_FATAL_DELAYED_THROTTLE_NAMED(rate, name, ...) ROS_LOG_DELAYED_THROTTLE(rate, ::ros::console::levels::Fatal, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, __VA_ARGS__)
+#define ROS_FATAL_STREAM_DELAYED_THROTTLE_NAMED(rate, name, args) ROS_LOG_STREAM_DELAYED_THROTTLE(rate, ::ros::console::levels::Fatal, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, args)
 #define ROS_FATAL_FILTER(filter, ...) ROS_LOG_FILTER(filter, ::ros::console::levels::Fatal, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__)
 #define ROS_FATAL_STREAM_FILTER(filter, args) ROS_LOG_STREAM_FILTER(filter, ::ros::console::levels::Fatal, ROSCONSOLE_DEFAULT_NAME, args)
 #define ROS_FATAL_FILTER_NAMED(filter, name, ...) ROS_LOG_FILTER(filter, ::ros::console::levels::Fatal, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, __VA_ARGS__)
diff --git a/tools/rosconsole/package.xml b/tools/rosconsole/package.xml
index d60e6e0..fdaf462 100644
--- a/tools/rosconsole/package.xml
+++ b/tools/rosconsole/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>rosconsole</name>
-  <version>1.11.10</version>
+  <version>1.11.11</version>
   <description>ROS console output library.</description>
   <maintainer email="dthomas at osrfoundation.org">Dirk Thomas</maintainer>
   <license>BSD</license>
diff --git a/tools/rosconsole/scripts/generate_macros.py b/tools/rosconsole/scripts/generate_macros.py
index 3245d7c..ce1f4dd 100755
--- a/tools/rosconsole/scripts/generate_macros.py
+++ b/tools/rosconsole/scripts/generate_macros.py
@@ -44,7 +44,7 @@ def add_macro(f, caps_name, enum_name):
     f.write('#define ROS_%s_STREAM_COND(cond, args)\n' %(caps_name))
     f.write('#define ROS_%s_COND_NAMED(cond, name, ...)\n' %(caps_name))
     f.write('#define ROS_%s_STREAM_COND_NAMED(cond, name, args)\n' %(caps_name))
-    
+
     f.write('#define ROS_%s_ONCE(...)\n' %(caps_name))
     f.write('#define ROS_%s_STREAM_ONCE(args)\n' %(caps_name))
     f.write('#define ROS_%s_ONCE_NAMED(name, ...)\n' %(caps_name))
@@ -53,7 +53,11 @@ def add_macro(f, caps_name, enum_name):
     f.write('#define ROS_%s_STREAM_THROTTLE(rate, args)\n' %(caps_name))
     f.write('#define ROS_%s_THROTTLE_NAMED(rate, name, ...)\n' %(caps_name))
     f.write('#define ROS_%s_STREAM_THROTTLE_NAMED(rate, name, args)\n' %(caps_name))
-    
+    f.write('#define ROS_%s_DELAYED_THROTTLE(rate, ...)\n' %(caps_name))
+    f.write('#define ROS_%s_STREAM_DELAYED_THROTTLE(rate, args)\n' %(caps_name))
+    f.write('#define ROS_%s_DELAYED_THROTTLE_NAMED(rate, name, ...)\n' %(caps_name))
+    f.write('#define ROS_%s_STREAM_DELAYED_THROTTLE_NAMED(rate, name, args)\n' %(caps_name))
+
     f.write('#define ROS_%s_FILTER(filter, ...)\n' %(caps_name))
     f.write('#define ROS_%s_STREAM_FILTER(filter, args)\n' %(caps_name))
     f.write('#define ROS_%s_FILTER_NAMED(filter, name, ...)\n' %(caps_name))
@@ -67,17 +71,22 @@ def add_macro(f, caps_name, enum_name):
     f.write('#define ROS_%s_STREAM_COND(cond, args) ROS_LOG_STREAM_COND(cond, ::ros::console::levels::%s, ROSCONSOLE_DEFAULT_NAME, args)\n' %(caps_name, enum_name))
     f.write('#define ROS_%s_COND_NAMED(cond, name, ...) ROS_LOG_COND(cond, ::ros::console::levels::%s, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, __VA_ARGS__)\n' %(caps_name, enum_name))
     f.write('#define ROS_%s_STREAM_COND_NAMED(cond, name, args) ROS_LOG_STREAM_COND(cond, ::ros::console::levels::%s, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, args)\n' %(caps_name, enum_name))
-    
+
     f.write('#define ROS_%s_ONCE(...) ROS_LOG_ONCE(::ros::console::levels::%s, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__)\n' %(caps_name, enum_name))
     f.write('#define ROS_%s_STREAM_ONCE(args) ROS_LOG_STREAM_ONCE(::ros::console::levels::%s, ROSCONSOLE_DEFAULT_NAME, args)\n' %(caps_name, enum_name))
     f.write('#define ROS_%s_ONCE_NAMED(name, ...) ROS_LOG_ONCE(::ros::console::levels::%s, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, __VA_ARGS__)\n' %(caps_name, enum_name))
     f.write('#define ROS_%s_STREAM_ONCE_NAMED(name, args) ROS_LOG_STREAM_ONCE(::ros::console::levels::%s, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, args)\n' %(caps_name, enum_name))
-    
+
     f.write('#define ROS_%s_THROTTLE(rate, ...) ROS_LOG_THROTTLE(rate, ::ros::console::levels::%s, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__)\n' %(caps_name, enum_name))
     f.write('#define ROS_%s_STREAM_THROTTLE(rate, args) ROS_LOG_STREAM_THROTTLE(rate, ::ros::console::levels::%s, ROSCONSOLE_DEFAULT_NAME, args)\n' %(caps_name, enum_name))
     f.write('#define ROS_%s_THROTTLE_NAMED(rate, name, ...) ROS_LOG_THROTTLE(rate, ::ros::console::levels::%s, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, __VA_ARGS__)\n' %(caps_name, enum_name))
     f.write('#define ROS_%s_STREAM_THROTTLE_NAMED(rate, name, args) ROS_LOG_STREAM_THROTTLE(rate, ::ros::console::levels::%s, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, args)\n' %(caps_name, enum_name))
-    
+
+    f.write('#define ROS_%s_DELAYED_THROTTLE(rate, ...) ROS_LOG_DELAYED_THROTTLE(rate, ::ros::console::levels::%s, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__)\n' %(caps_name, enum_name))
+    f.write('#define ROS_%s_STREAM_DELAYED_THROTTLE(rate, args) ROS_LOG_STREAM_DELAYED_THROTTLE(rate, ::ros::console::levels::%s, ROSCONSOLE_DEFAULT_NAME, args)\n' %(caps_name, enum_name))
+    f.write('#define ROS_%s_DELAYED_THROTTLE_NAMED(rate, name, ...) ROS_LOG_DELAYED_THROTTLE(rate, ::ros::console::levels::%s, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, __VA_ARGS__)\n' %(caps_name, enum_name))
+    f.write('#define ROS_%s_STREAM_DELAYED_THROTTLE_NAMED(rate, name, args) ROS_LOG_STREAM_DELAYED_THROTTLE(rate, ::ros::console::levels::%s, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, args)\n' %(caps_name, enum_name))
+
     f.write('#define ROS_%s_FILTER(filter, ...) ROS_LOG_FILTER(filter, ::ros::console::levels::%s, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__)\n' %(caps_name, enum_name))
     f.write('#define ROS_%s_STREAM_FILTER(filter, args) ROS_LOG_STREAM_FILTER(filter, ::ros::console::levels::%s, ROSCONSOLE_DEFAULT_NAME, args)\n' %(caps_name, enum_name))
     f.write('#define ROS_%s_FILTER_NAMED(filter, name, ...) ROS_LOG_FILTER(filter, ::ros::console::levels::%s, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, __VA_ARGS__)\n' %(caps_name, enum_name))
diff --git a/tools/rosconsole/test/utest.cpp b/tools/rosconsole/test/utest.cpp
index e86538a..47e8552 100644
--- a/tools/rosconsole/test/utest.cpp
+++ b/tools/rosconsole/test/utest.cpp
@@ -701,6 +701,48 @@ TEST(RosConsole, throttle)
   logger->removeAppender(appender);
 }
 
+void delayedThrottleFunc()
+{
+  ROS_LOG_DELAYED_THROTTLE(0.5, ros::console::levels::Info, ROSCONSOLE_DEFAULT_NAME, "Hello");
+}
+
+void delayedThrottleFunc2()
+{
+  ROS_LOG_DELAYED_THROTTLE(0.5, ros::console::levels::Info, ROSCONSOLE_DEFAULT_NAME, "Hello2");
+}
+
+TEST(RosConsole, delayedThrottle)
+{
+  log4cxx::LoggerPtr logger = log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME);
+
+  TestAppender* appender = new TestAppender;
+  logger->addAppender(appender);
+
+  ros::Time start = ros::Time::now();
+  while (ros::Time::now() <= start + ros::Duration(0.4))
+  {
+    delayedThrottleFunc();
+    ros::Duration(0.01).sleep();
+  }
+
+  EXPECT_EQ(appender->info_.size(), 0ULL);
+
+  const int pre_count = appender->info_.size();
+  start = ros::Time::now();
+  while (ros::Time::now() <= start + ros::Duration(0.6))
+  {
+    delayedThrottleFunc2();
+    ros::Duration(0.01).sleep();
+  }
+
+  const int post_count = appender->info_.size();
+
+  EXPECT_EQ(post_count, pre_count + 1);
+
+  logger->removeAppender(appender);
+}
+
+
 void onceStreamFunc()
 {
   ROS_LOG_STREAM_ONCE(ros::console::levels::Info, ROSCONSOLE_DEFAULT_NAME, "Hello");
@@ -747,6 +789,47 @@ TEST(RosConsole, throttleStream)
   logger->removeAppender(appender);
 }
 
+void delayedThrottleStreamFunc()
+{
+  ROS_LOG_STREAM_DELAYED_THROTTLE(0.5, ros::console::levels::Info, ROSCONSOLE_DEFAULT_NAME, "Hello");
+}
+
+void delayedThrottleStreamFunc2()
+{
+  ROS_LOG_STREAM_DELAYED_THROTTLE(0.5, ros::console::levels::Info, ROSCONSOLE_DEFAULT_NAME, "Hello2");
+}
+
+TEST(RosConsole, delayedStreamThrottle)
+{
+  log4cxx::LoggerPtr logger = log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME);
+
+  TestAppender* appender = new TestAppender;
+  logger->addAppender(appender);
+
+  ros::Time start = ros::Time::now();
+  while (ros::Time::now() <= start + ros::Duration(0.4))
+  {
+    delayedThrottleStreamFunc();
+    ros::Duration(0.01).sleep();
+  }
+
+  EXPECT_EQ(appender->info_.size(), 0ULL);
+
+  const int pre_count = appender->info_.size();
+  start = ros::Time::now();
+  while (ros::Time::now() <= start + ros::Duration(0.6))
+  {
+    delayedThrottleStreamFunc2();
+    ros::Duration(0.01).sleep();
+  }
+
+  const int post_count = appender->info_.size();
+
+  EXPECT_EQ(post_count, pre_count + 1);
+
+  logger->removeAppender(appender);
+}
+
 TEST(RosConsole, basicFilter)
 {
   log4cxx::LoggerPtr logger = log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME);
diff --git a/tools/rosgraph/CHANGELOG.rst b/tools/rosgraph/CHANGELOG.rst
index d8d34b9..601f86a 100644
--- a/tools/rosgraph/CHANGELOG.rst
+++ b/tools/rosgraph/CHANGELOG.rst
@@ -2,6 +2,9 @@
 Changelog for package rosgraph
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.11.11 (2015-04-16)
+--------------------
+
 1.11.10 (2014-12-22)
 --------------------
 * rosconsole format for rospy (`#517 <https://github.com/ros/ros_comm/issues/517>`_)
diff --git a/tools/rosgraph/package.xml b/tools/rosgraph/package.xml
index d3993f4..c057ec6 100644
--- a/tools/rosgraph/package.xml
+++ b/tools/rosgraph/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>rosgraph</name>
-  <version>1.11.10</version>
+  <version>1.11.11</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/roslaunch/CHANGELOG.rst b/tools/roslaunch/CHANGELOG.rst
index 7e45be5..e58a7ab 100644
--- a/tools/roslaunch/CHANGELOG.rst
+++ b/tools/roslaunch/CHANGELOG.rst
@@ -2,6 +2,9 @@
 Changelog for package roslaunch
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.11.11 (2015-04-16)
+--------------------
+
 1.11.10 (2014-12-22)
 --------------------
 * fix exception at roscore startup if python has IPv6 disabled (`#515 <https://github.com/ros/ros_comm/issues/515>`_)
diff --git a/tools/roslaunch/package.xml b/tools/roslaunch/package.xml
index 2404590..268b4b9 100644
--- a/tools/roslaunch/package.xml
+++ b/tools/roslaunch/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>roslaunch</name>
-  <version>1.11.10</version>
+  <version>1.11.11</version>
   <description>
     roslaunch is a tool for easily launching multiple ROS <a
     href="http://ros.org/wiki/Nodes">nodes</a> locally and remotely
diff --git a/tools/rosmaster/CHANGELOG.rst b/tools/rosmaster/CHANGELOG.rst
index b44e00a..5e7141b 100644
--- a/tools/rosmaster/CHANGELOG.rst
+++ b/tools/rosmaster/CHANGELOG.rst
@@ -2,6 +2,9 @@
 Changelog for package rosmaster
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.11.11 (2015-04-16)
+--------------------
+
 1.11.10 (2014-12-22)
 --------------------
 * fix closing sockets properly on node shutdown (`#495 <https://github.com/ros/ros_comm/issues/495>`_)
diff --git a/tools/rosmaster/package.xml b/tools/rosmaster/package.xml
index 01617e2..80d20bf 100644
--- a/tools/rosmaster/package.xml
+++ b/tools/rosmaster/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>rosmaster</name>
-  <version>1.11.10</version>
+  <version>1.11.11</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 a77d041..1bb4ead 100644
--- a/tools/rosmsg/CHANGELOG.rst
+++ b/tools/rosmsg/CHANGELOG.rst
@@ -2,6 +2,9 @@
 Changelog for package rosmsg
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.11.11 (2015-04-16)
+--------------------
+
 1.11.10 (2014-12-22)
 --------------------
 
diff --git a/tools/rosmsg/package.xml b/tools/rosmsg/package.xml
index b5cd11f..bd1668f 100644
--- a/tools/rosmsg/package.xml
+++ b/tools/rosmsg/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>rosmsg</name>
-  <version>1.11.10</version>
+  <version>1.11.11</version>
   <description>
     rosmsg contains two command-line tools: <tt>rosmsg</tt> and
     <tt>rossrv</tt>. <tt>rosmsg</tt> is a command-line tool for
diff --git a/tools/rosnode/CHANGELOG.rst b/tools/rosnode/CHANGELOG.rst
index c9056c4..3da919f 100644
--- a/tools/rosnode/CHANGELOG.rst
+++ b/tools/rosnode/CHANGELOG.rst
@@ -2,6 +2,9 @@
 Changelog for package rosnode
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.11.11 (2015-04-16)
+--------------------
+
 1.11.10 (2014-12-22)
 --------------------
 
diff --git a/tools/rosnode/package.xml b/tools/rosnode/package.xml
index add1f46..db2c036 100644
--- a/tools/rosnode/package.xml
+++ b/tools/rosnode/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>rosnode</name>
-  <version>1.11.10</version>
+  <version>1.11.11</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 64fb266..39c8ec4 100644
--- a/tools/rosout/CHANGELOG.rst
+++ b/tools/rosout/CHANGELOG.rst
@@ -2,6 +2,9 @@
 Changelog for package rosout
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.11.11 (2015-04-16)
+--------------------
+
 1.11.10 (2014-12-22)
 --------------------
 
diff --git a/tools/rosout/package.xml b/tools/rosout/package.xml
index fc38044..39d9c69 100644
--- a/tools/rosout/package.xml
+++ b/tools/rosout/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>rosout</name>
-  <version>1.11.10</version>
+  <version>1.11.11</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 db0f75f..c810194 100644
--- a/tools/rosparam/CHANGELOG.rst
+++ b/tools/rosparam/CHANGELOG.rst
@@ -2,6 +2,9 @@
 Changelog for package rosparam
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.11.11 (2015-04-16)
+--------------------
+
 1.11.10 (2014-12-22)
 --------------------
 
diff --git a/tools/rosparam/package.xml b/tools/rosparam/package.xml
index bf64e1e..4ca9b55 100644
--- a/tools/rosparam/package.xml
+++ b/tools/rosparam/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>rosparam</name>
-  <version>1.11.10</version>
+  <version>1.11.11</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 0c6c559..59fb0fc 100644
--- a/tools/rosservice/CHANGELOG.rst
+++ b/tools/rosservice/CHANGELOG.rst
@@ -2,6 +2,9 @@
 Changelog for package rosservice
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.11.11 (2015-04-16)
+--------------------
+
 1.11.10 (2014-12-22)
 --------------------
 
diff --git a/tools/rosservice/package.xml b/tools/rosservice/package.xml
index 0b3df87..5e97488 100644
--- a/tools/rosservice/package.xml
+++ b/tools/rosservice/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>rosservice</name>
-  <version>1.11.10</version>
+  <version>1.11.11</version>
   <description>
     rosservice contains the rosservice command-line tool for listing
     and querying ROS <a
diff --git a/tools/rostest/CHANGELOG.rst b/tools/rostest/CHANGELOG.rst
index 45b7648..4559dfd 100644
--- a/tools/rostest/CHANGELOG.rst
+++ b/tools/rostest/CHANGELOG.rst
@@ -2,6 +2,10 @@
 Changelog for package rostest
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.11.11 (2015-04-16)
+--------------------
+* add DEPENDENCIES option to CMake function add_rostest (`#546 <https://github.com/ros/ros_comm/issues/546>`_)
+
 1.11.10 (2014-12-22)
 --------------------
 
diff --git a/tools/rostest/cmake/rostest-extras.cmake.em b/tools/rostest/cmake/rostest-extras.cmake.em
index fdd3fa7..fd67d11 100644
--- a/tools/rostest/cmake/rostest-extras.cmake.em
+++ b/tools/rostest/cmake/rostest-extras.cmake.em
@@ -15,7 +15,7 @@ function(add_rostest file)
   set(ROSTEST_EXE "${rostest_DIR}/../../../@(CATKIN_GLOBAL_BIN_DESTINATION)/rostest")
 @[end if]@
 
-  cmake_parse_arguments(_rostest "" "WORKING_DIRECTORY" "ARGS" ${ARGN})
+  cmake_parse_arguments(_rostest "" "WORKING_DIRECTORY" "ARGS;DEPENDENCIES" ${ARGN})
 
   # Check that the file exists, #1621
   set(_file_name _file_name-NOTFOUND)
@@ -53,7 +53,7 @@ function(add_rostest file)
   get_filename_component(_output_name ${_testname} NAME_WE)
   set(_output_name "${_output_name}.xml")
   set(cmd "${ROSTEST_EXE} --pkgdir=${PROJECT_SOURCE_DIR} --package=${PROJECT_NAME} --results-filename ${_output_name} ${_file_name} ${_rostest_ARGS}")
-  catkin_run_tests_target("rostest" ${_testname} "rostest-${_output_name}" COMMAND ${cmd} WORKING_DIRECTORY ${_rostest_WORKING_DIRECTORY})
+  catkin_run_tests_target("rostest" ${_testname} "rostest-${_output_name}" COMMAND ${cmd} WORKING_DIRECTORY ${_rostest_WORKING_DIRECTORY} DEPENDENCIES ${_rostest_DEPENDENCIES})
 endfunction()
 
 #
diff --git a/tools/rostest/package.xml b/tools/rostest/package.xml
index db00226..d7e130e 100644
--- a/tools/rostest/package.xml
+++ b/tools/rostest/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>rostest</name>
-  <version>1.11.10</version>
+  <version>1.11.11</version>
   <description>
      Integration test suite based on roslaunch that is compatible with xUnit frameworks.
   </description>
diff --git a/tools/rostopic/CHANGELOG.rst b/tools/rostopic/CHANGELOG.rst
index 1e6fb6d..9a1d22a 100644
--- a/tools/rostopic/CHANGELOG.rst
+++ b/tools/rostopic/CHANGELOG.rst
@@ -2,6 +2,9 @@
 Changelog for package rostopic
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.11.11 (2015-04-16)
+--------------------
+
 1.11.10 (2014-12-22)
 --------------------
 * add support for fixed-width floating-point and integer array values (`#400 <https://github.com/ros/ros_comm/issues/400>`_)
diff --git a/tools/rostopic/package.xml b/tools/rostopic/package.xml
index e8a03e1..b7cf1d9 100644
--- a/tools/rostopic/package.xml
+++ b/tools/rostopic/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>rostopic</name>
-  <version>1.11.10</version>
+  <version>1.11.11</version>
   <description>
     rostopic contains the rostopic command-line tool for displaying
     debug information about
diff --git a/tools/topic_tools/CHANGELOG.rst b/tools/topic_tools/CHANGELOG.rst
index e67a173..1c67b78 100644
--- a/tools/topic_tools/CHANGELOG.rst
+++ b/tools/topic_tools/CHANGELOG.rst
@@ -2,6 +2,9 @@
 Changelog for package topic_tools
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.11.11 (2015-04-16)
+--------------------
+
 1.11.10 (2014-12-22)
 --------------------
 
diff --git a/tools/topic_tools/package.xml b/tools/topic_tools/package.xml
index 2a16bb2..245645e 100644
--- a/tools/topic_tools/package.xml
+++ b/tools/topic_tools/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>topic_tools</name>
-  <version>1.11.10</version>
+  <version>1.11.11</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/utilities/message_filters/CHANGELOG.rst b/utilities/message_filters/CHANGELOG.rst
index 8299fac..b15e72e 100644
--- a/utilities/message_filters/CHANGELOG.rst
+++ b/utilities/message_filters/CHANGELOG.rst
@@ -2,6 +2,10 @@
 Changelog for package message_filters
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.11.11 (2015-04-16)
+--------------------
+* implement message filter cache in Python (`#599 <https://github.com/ros/ros_comm/pull/599>`_)
+
 1.11.10 (2014-12-22)
 --------------------
 
diff --git a/utilities/message_filters/CMakeLists.txt b/utilities/message_filters/CMakeLists.txt
index e40f480..c095f0c 100644
--- a/utilities/message_filters/CMakeLists.txt
+++ b/utilities/message_filters/CMakeLists.txt
@@ -81,4 +81,5 @@ if(CATKIN_ENABLE_TESTING)
 
   # Unit test of the approximate synchronizer
   catkin_add_nosetests(test/test_approxsync.py)
+  catkin_add_nosetests(test/test_message_filters_cache.py)
 endif()
diff --git a/utilities/message_filters/package.xml b/utilities/message_filters/package.xml
index fbd562c..2fdee47 100644
--- a/utilities/message_filters/package.xml
+++ b/utilities/message_filters/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>message_filters</name>
-  <version>1.11.10</version>
+  <version>1.11.11</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 931c624..dc7d7cf 100644
--- a/utilities/message_filters/src/message_filters/__init__.py
+++ b/utilities/message_filters/src/message_filters/__init__.py
@@ -90,15 +90,67 @@ class Cache(SimpleFilter):
         SimpleFilter.__init__(self)
         self.connectInput(f)
         self.cache_size = cache_size
+        # Array to store messages
+        self.cache_msgs = []
+        # Array to store msgs times, auxiliary structure to facilitate
+        # sorted insertion
+        self.cache_times = []
 
     def connectInput(self, f):
         self.incoming_connection = f.registerCallback(self.add)
 
     def add(self, msg):
-        # Add msg to cache... XXX TODO
-
+        # Cannot use message filters with non-stamped messages
+        if not hasattr(msg, 'header') or not hasattr(msg.header, 'stamp'):
+            rospy.logwarn("Cannot use message filters with non-stamped messages")
+            return
+
+        # Insert sorted
+        stamp = msg.header.stamp
+        self.cache_times.append(stamp)
+        self.cache_msgs.append(msg)
+
+        # Implement a ring buffer, discard older if oversized
+        if (len(self.cache_msgs) > self.cache_size):
+            del self.cache_msgs[0]
+            del self.cache_times[0]
+
+        # Signal new input
         self.signalMessage(msg)
 
+    def getInterval(self, from_stamp, to_stamp):
+        """Query the current cache content between from_stamp to to_stamp."""
+        assert from_stamp <= to_stamp
+        return [m for m in self.cache_msgs
+                if m.header.stamp >= from_stamp and m.header.stamp <= to_stamp]
+
+    def getElemAfterTime(self, stamp):
+        """Return the oldest element after or equal the passed time stamp."""
+        newer = [m for m in self.cache_msgs if m.header.stamp >= stamp]
+        if not newer:
+            return None
+        return newer[0]
+
+    def getElemBeforeTime(self, stamp):
+        """Return the newest element before or equal the passed time stamp."""
+        older = [m for m in self.cache_msgs if m.header.stamp <= stamp]
+        if not older:
+            return None
+        return older[-1]
+
+    def getLastestTime(self):
+        """Return the newest recorded timestamp."""
+        if not self.cache_times:
+            return None
+        return self.cache_times[-1]
+
+    def getOldestTime(self):
+        """Return the oldest recorded timestamp."""
+        if not self.cache_times:
+            return None
+        return self.cache_times[0]
+
+
 class TimeSynchronizer(SimpleFilter):
 
     """
diff --git a/utilities/message_filters/test/test_message_filters_cache.py b/utilities/message_filters/test/test_message_filters_cache.py
new file mode 100644
index 0000000..7569212
--- /dev/null
+++ b/utilities/message_filters/test/test_message_filters_cache.py
@@ -0,0 +1,127 @@
+#!/usr/bin/env python
+# Software License Agreement (BSD License)
+#
+# Copyright 2015 Martin Llofriu, Open Source Robotics Foundation, 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 the Willow Garage 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.
+
+import rospy
+import unittest
+
+from std_msgs.msg import String
+
+from message_filters import Cache, Subscriber
+
+PKG = 'message_filters'
+
+
+class AnonymMsg:
+    class AnonymHeader:
+        stamp = None
+
+        def __init__(self):
+            self.stamp = rospy.Time()
+
+    header = None
+
+    def __init__(self):
+        self.header = AnonymMsg.AnonymHeader()
+
+
+class TestCache(unittest.TestCase):
+
+    def test_all_funcs(self):
+        sub = Subscriber("/empty", String)
+        cache = Cache(sub, 5)
+
+        msg = AnonymMsg()
+        msg.header.stamp = rospy.Time(0)
+        cache.add(msg)
+
+        msg = AnonymMsg()
+        msg.header.stamp = rospy.Time(1)
+        cache.add(msg)
+
+        msg = AnonymMsg()
+        msg.header.stamp = rospy.Time(2)
+        cache.add(msg)
+
+        msg = AnonymMsg()
+        msg.header.stamp = rospy.Time(3)
+        cache.add(msg)
+
+        msg = AnonymMsg()
+        msg.header.stamp = rospy.Time(4)
+        cache.add(msg)
+
+        l = len(cache.getInterval(rospy.Time(2.5),
+                                  rospy.Time(3.5)))
+        self.assertEquals(l, 1, "invalid number of messages" +
+                                " returned in getInterval 1")
+
+        l = len(cache.getInterval(rospy.Time(2),
+                                  rospy.Time(3)))
+        self.assertEquals(l, 2, "invalid number of messages" +
+                                " returned in getInterval 2")
+
+        l = len(cache.getInterval(rospy.Time(0),
+                                  rospy.Time(4)))
+        self.assertEquals(l, 5, "invalid number of messages" +
+                                " returned in getInterval 3")
+
+        s = cache.getElemAfterTime(rospy.Time(0)).header.stamp
+        self.assertEqual(s, rospy.Time(0),
+                         "invalid msg return by getElemAfterTime")
+
+        s = cache.getElemBeforeTime(rospy.Time(3.5)).header.stamp
+        self.assertEqual(s, rospy.Time(3),
+                         "invalid msg return by getElemBeforeTime")
+
+        s = cache.getLastestTime()
+        self.assertEqual(s, rospy.Time(4),
+                         "invalid stamp return by getLastestTime")
+
+        s = cache.getOldestTime()
+        self.assertEqual(s, rospy.Time(0),
+                         "invalid stamp return by getOldestTime")
+
+        # Add another msg to fill the buffer
+        msg = AnonymMsg()
+        msg.header.stamp = rospy.Time(5)
+        cache.add(msg)
+
+        # Test that it discarded the right one
+        s = cache.getOldestTime()
+        self.assertEqual(s, rospy.Time(1),
+                         "wrong message discarded")
+
+
+if __name__ == '__main__':
+    import rosunit
+    rosunit.unitrun(PKG, 'test_message_filters_cache', TestCache)
diff --git a/utilities/roslz4/CHANGELOG.rst b/utilities/roslz4/CHANGELOG.rst
index 9ca518c..22eac61 100644
--- a/utilities/roslz4/CHANGELOG.rst
+++ b/utilities/roslz4/CHANGELOG.rst
@@ -2,6 +2,10 @@
 Changelog for package roslz4
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.11.11 (2015-04-16)
+--------------------
+* fix import of compiled library with Python 3.x (`#563 <https://github.com/ros/ros_comm/pull/563>`_)
+
 1.11.10 (2014-12-22)
 --------------------
 * disable lz4 Python bindings on Android (`#521 <https://github.com/ros/ros_comm/pull/521>`_)
diff --git a/utilities/roslz4/package.xml b/utilities/roslz4/package.xml
index 1d05249..350c4ec 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.11.10</version>
+  <version>1.11.11</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/roslz4/src/roslz4/__init__.py b/utilities/roslz4/src/roslz4/__init__.py
index 09e7335..7acf2f5 100644
--- a/utilities/roslz4/src/roslz4/__init__.py
+++ b/utilities/roslz4/src/roslz4/__init__.py
@@ -30,7 +30,7 @@
 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
 # POSSIBILITY OF SUCH DAMAGE.
 
-from _roslz4 import *
+from ._roslz4 import *
 
 def compress(data):
     compressor = LZ4Compressor()
diff --git a/utilities/roswtf/CHANGELOG.rst b/utilities/roswtf/CHANGELOG.rst
index 61025ec..c544776 100644
--- a/utilities/roswtf/CHANGELOG.rst
+++ b/utilities/roswtf/CHANGELOG.rst
@@ -2,6 +2,10 @@
 Changelog for package roswtf
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.11.11 (2015-04-16)
+--------------------
+* support IPv6 addresses containing percentage symbols (`#585 <https://github.com/ros/ros_comm/issues/585>`_)
+
 1.11.10 (2014-12-22)
 --------------------
 
diff --git a/utilities/roswtf/package.xml b/utilities/roswtf/package.xml
index d7d15fb..b304593 100644
--- a/utilities/roswtf/package.xml
+++ b/utilities/roswtf/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>roswtf</name>
-  <version>1.11.10</version>
+  <version>1.11.11</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/src/roswtf/network.py b/utilities/roswtf/src/roswtf/network.py
index d208cfa..1f3cd8a 100644
--- a/utilities/roswtf/src/roswtf/network.py
+++ b/utilities/roswtf/src/roswtf/network.py
@@ -53,7 +53,11 @@ def ip_check(ctx):
 
     remote_ips = list(set(global_ips) - set(local_addrs))
     if remote_ips:
-        return "Local hostname [%s] resolves to [%s], which does not appear to be a local IP address %s."%(socket.gethostname(), ','.join(remote_ips), str(local_addrs))
+        retval = "Local hostname [%s] resolves to [%s], which does not appear to be a local IP address %s." % (socket.gethostname(), ','.join(remote_ips), str(local_addrs))
+        # IPv6 support % to denote zone/scope ids. The value is expanded
+        # in other functions, this is why we are using replace command in
+        # the return. For more info https://github.com/ros/ros_comm/pull/598
+        return retval.replace('%', '%%')
 
 # suggestion by mquigley based on laptop dhcp issues    
 def ros_hostname_check(ctx):
diff --git a/utilities/xmlrpcpp/CHANGELOG.rst b/utilities/xmlrpcpp/CHANGELOG.rst
index 26ce348..5130de0 100644
--- a/utilities/xmlrpcpp/CHANGELOG.rst
+++ b/utilities/xmlrpcpp/CHANGELOG.rst
@@ -2,6 +2,9 @@
 Changelog for package xmlrpcpp
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.11.11 (2015-04-16)
+--------------------
+
 1.11.10 (2014-12-22)
 --------------------
 * improve Android support (`#537 <https://github.com/ros/ros_comm/pull/537>`_)
diff --git a/utilities/xmlrpcpp/package.xml b/utilities/xmlrpcpp/package.xml
index 685afd2..e71b251 100644
--- a/utilities/xmlrpcpp/package.xml
+++ b/utilities/xmlrpcpp/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>xmlrpcpp</name>
-  <version>1.11.10</version>
+  <version>1.11.11</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-comm.git



More information about the debian-science-commits mailing list