[ros-ros-comm] 02/16: Imported Upstream version 1.12.0

Leopold Palomo-Avellaneda leo at alaxarxa.net
Fri May 20 21:20:29 UTC 2016


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

lepalom-guest pushed a commit to branch master
in repository ros-ros-comm.

commit 2bdc9a79bbf34f8082b741a397c1dbc43ae3cde5
Author: Leopold Palomo-Avellaneda <leopold.palomo at upc.edu>
Date:   Thu Apr 7 09:35:33 2016 +0200

    Imported Upstream version 1.12.0
---
 .travis.yml                                        |  37 ----
 clients/roscpp/CHANGELOG.rst                       |  17 ++
 clients/roscpp/CMakeLists.txt                      |   6 +-
 .../roscpp/include/ros/advertise_service_options.h |   6 +-
 clients/roscpp/include/ros/forwards.h              |   1 +
 clients/roscpp/include/ros/node_handle.h           |  44 +++--
 clients/roscpp/include/ros/param.h                 |  13 +-
 .../roscpp/include/ros/service_callback_helper.h   |   2 +-
 clients/roscpp/include/ros/subscribe_options.h     |   4 +-
 clients/roscpp/include/ros/subscriber_link.h       |   4 +-
 clients/roscpp/include/ros/timer_manager.h         |   4 +-
 clients/roscpp/include/ros/transport/transport.h   |   2 +-
 clients/roscpp/package.xml                         |   2 +-
 clients/roscpp/src/libros/callback_queue.cpp       |   2 +-
 clients/roscpp/src/libros/connection.cpp           |   1 +
 clients/roscpp/src/libros/connection_manager.cpp   |  14 +-
 clients/roscpp/src/libros/init.cpp                 |   1 +
 clients/roscpp/src/libros/node_handle.cpp          |   9 +-
 clients/roscpp/src/libros/param.cpp                |  30 +++
 clients/roscpp/src/libros/publication.cpp          |   6 +-
 clients/roscpp/src/libros/publisher.cpp            |   4 +-
 clients/roscpp/src/libros/rosout_appender.cpp      |   4 +-
 clients/roscpp/src/libros/service.cpp              |   2 +-
 clients/roscpp/src/libros/service_client_link.cpp  |   2 +
 clients/roscpp/src/libros/service_manager.cpp      |  10 +-
 clients/roscpp/src/libros/service_publication.cpp  |   2 +-
 clients/roscpp/src/libros/service_server.cpp       |   4 +-
 clients/roscpp/src/libros/service_server_link.cpp  |   5 +-
 clients/roscpp/src/libros/statistics.cpp           |   7 +-
 clients/roscpp/src/libros/subscriber.cpp           |   4 +-
 clients/roscpp/src/libros/subscription.cpp         |  27 +--
 clients/roscpp/src/libros/topic_manager.cpp        |  24 +--
 .../roscpp/src/libros/transport/transport_tcp.cpp  |   2 +-
 .../roscpp/src/libros/transport/transport_udp.cpp  |   2 +-
 .../roscpp/src/libros/transport_publisher_link.cpp |   5 +-
 .../src/libros/transport_subscriber_link.cpp       |   3 +
 clients/roscpp/src/libros/xmlrpc_manager.cpp       |   1 +
 clients/rospy/CHANGELOG.rst                        |  10 +
 clients/rospy/package.xml                          |   2 +-
 clients/rospy/src/rospy/core.py                    |   5 +-
 clients/rospy/src/rospy/numpy_msg.py               |   8 +-
 clients/rospy/src/rospy/rostime.py                 |   4 +-
 clients/rospy/src/rospy/timer.py                   |   2 +-
 ros_comm/CHANGELOG.rst                             |   9 +
 ros_comm/package.xml                               |   2 +-
 test/test_rosbag/CMakeLists.txt                    |   5 +
 test/test_rosbag/package.xml                       |   2 +-
 test/test_rosbag/test/test_bag.cpp.in              |   4 +-
 test/test_rosbag_storage/package.xml               |   2 +-
 test/test_roscpp/CMakeLists.txt                    |   4 +
 test/test_roscpp/package.xml                       |   2 +-
 test/test_roscpp/perf/CMakeLists.txt               |   2 +-
 test/test_roscpp/perf/src/intra.cpp                |   6 +-
 test/test_roscpp/perf_serialization/CMakeLists.txt |   2 +-
 test/test_roscpp/test/src/CMakeLists.txt           | 142 +++++++--------
 test/test_roscpp/test/src/handles.cpp              |  16 +-
 .../test/src/intraprocess_subscriptions.cpp        |  18 +-
 test/test_roscpp/test/src/loads_of_publishers.cpp  |   3 +-
 test/test_roscpp/test/src/multiple_init_fini.cpp   |   2 +-
 .../test/src/nonconst_subscriptions.cpp            |   8 +-
 test/test_roscpp/test/src/params.cpp               |   6 +
 test/test_roscpp/test/src/service_adv_a.cpp        |   2 +-
 test/test_roscpp/test/src/service_adv_multiple.cpp |   4 +-
 test/test_roscpp/test/src/service_adv_unadv.cpp    |   4 +-
 test/test_roscpp/test/src/service_adv_zombie.cpp   |   2 +-
 .../test/src/service_callback_types.cpp            |  16 +-
 test/test_roscpp/test/src/service_deadlock.cpp     |   2 +-
 test/test_roscpp/test/src/service_exception.cpp    |   2 +-
 test/test_roscpp/test/src/service_wait_a_adv_b.cpp |   2 +-
 .../stamped_topic_statistics_empty_timestamp.cpp   |   2 +-
 test/test_roscpp/test/src/subscribe_empty.cpp      |   2 +-
 test/test_roscpp/test/src/subscribe_retry_tcp.cpp  |   2 +-
 test/test_roscpp/test/src/subscribe_star.cpp       |   8 +-
 .../test_roscpp/test/src/subscribe_unsubscribe.cpp |   4 +-
 .../test/src/subscribe_unsubscribe_repeatedly.cpp  |   2 +-
 test/test_roscpp/test/src/timer_callbacks.cpp      |   8 +-
 test/test_roscpp/test/test_callback_queue.cpp      |  28 +--
 test/test_roscpp/test/test_spinners.cpp            |   2 +-
 test/test_roscpp/test/test_subscription_queue.cpp  |  37 ++--
 test/test_roscpp/test/test_transport_tcp.cpp       |   8 +-
 test/test_roscpp/test_serialization/CMakeLists.txt |   8 +-
 test/test_roscpp/test_serialization/src/helpers.h  |   7 +-
 .../test_serialization/src/pre_deserialize.cpp     |  12 +-
 .../test_serialization/src/serialization.cpp       |   2 +-
 test/test_rosgraph/package.xml                     |   2 +-
 test/test_roslaunch/package.xml                    |   2 +-
 test/test_roslib_comm/package.xml                  |   2 +-
 test/test_roslib_comm/test/setup.cfg               |   4 -
 test/test_rosmaster/package.xml                    |   2 +-
 test/test_rosmaster/test/setup.cfg                 |   4 -
 test/test_rosparam/package.xml                     |   2 +-
 .../test/{test_rosparam.py => check_rosparam.py}   |  20 ++
 ...ne.py => check_rosparam_command_line_online.py} |   0
 test/test_rosparam/test/rosparam.test              |   4 +-
 test/test_rosparam/test/setup.cfg                  |   5 -
 .../test/test_rosparam_command_line_offline.py     |   2 +-
 test/test_rospy/package.xml                        |   2 +-
 test/test_rospy/test/unit/setup.cfg                |   4 -
 test/test_rospy/test/unit/test_rospy_numpy.py      |   9 +
 test/test_rosservice/package.xml                   |   2 +-
 .../{test_rosservice.py => check_rosservice.py}    |   0
 ....py => check_rosservice_command_line_online.py} |   0
 test/test_rosservice/test/rosservice.test          |   2 +-
 test/test_rosservice/test/rosservice_unit.test     |   2 +-
 test/test_rosservice/test/setup.cfg                |   3 -
 test/test_rostopic/package.xml                     |   2 +-
 tools/rosbag/CHANGELOG.rst                         |  11 ++
 tools/rosbag/CMakeLists.txt                        |   5 +
 tools/rosbag/include/rosbag/player.h               |   5 +-
 tools/rosbag/package.xml                           |   2 +-
 tools/rosbag/src/player.cpp                        |   6 +-
 tools/rosbag/src/recorder.cpp                      |  20 +-
 tools/rosbag_storage/CHANGELOG.rst                 |  11 ++
 tools/rosbag_storage/CMakeLists.txt                |   4 +
 tools/rosbag_storage/include/rosbag/bag.h          |   8 +-
 tools/rosbag_storage/package.xml                   |   2 +-
 tools/rosbag_storage/src/bag.cpp                   |   5 +-
 tools/rosbag_storage/src/chunked_file.cpp          |   7 +-
 tools/rosbag_storage/src/lz4_stream.cpp            |   2 +-
 tools/rosconsole/CHANGELOG.rst                     |  12 ++
 tools/rosconsole/CMakeLists.txt                    |   4 +
 tools/rosconsole/include/ros/console.h             |   3 +
 tools/rosconsole/package.xml                       |   2 +-
 .../src/rosconsole/impl/rosconsole_log4cxx.cpp     |   1 +
 tools/rosconsole/src/rosconsole/rosconsole.cpp     |  34 ++--
 tools/rosconsole/test/thread_test.cpp              |   2 +-
 tools/rosconsole/test/utest.cpp                    |   4 +-
 tools/rosgraph/CHANGELOG.rst                       |  12 ++
 tools/rosgraph/package.xml                         |   2 +-
 tools/rosgraph/src/rosgraph/network.py             |  24 +--
 tools/rosgraph/src/rosgraph/roslogging.py          |   2 +-
 tools/rosgraph/test/setup.cfg                      |   4 -
 tools/roslaunch/CHANGELOG.rst                      |  13 ++
 tools/roslaunch/package.xml                        |   2 +-
 tools/roslaunch/src/roslaunch/core.py              |   2 +-
 tools/roslaunch/src/roslaunch/loader.py            |  13 +-
 tools/roslaunch/src/roslaunch/remoteprocess.py     |   2 +-
 tools/roslaunch/src/roslaunch/rlutil.py            |  17 +-
 tools/roslaunch/src/roslaunch/scriptapi.py         |   2 +-
 tools/roslaunch/src/roslaunch/xmlloader.py         |  18 +-
 tools/roslaunch/test/unit/setup.cfg                |   5 -
 .../test/unit/test_roslaunch_dump_params.py        |   0
 tools/roslaunch/test/unit/test_xmlloader.py        | 111 ++++++++++++
 tools/roslaunch/test/xml/test-arg-all.xml          |  48 +++++
 .../test/xml/test-arg-invalid-include.xml          |   5 +
 .../test/xml/test-arg-invalid-include2.xml         |   6 +
 .../test/xml/test-arg-invalid-included.xml         |   3 +
 .../roslaunch/test/xml/test-arg-valid-include.xml  |   5 +
 tools/rosmaster/CHANGELOG.rst                      |   9 +
 tools/rosmaster/package.xml                        |   2 +-
 tools/rosmaster/src/rosmaster/threadpool.py        |   2 +-
 tools/rosmsg/CHANGELOG.rst                         |  10 +
 tools/rosmsg/package.xml                           |   2 +-
 tools/rosmsg/src/rosmsg/__init__.py                |   8 +-
 tools/rosmsg/test/setup.cfg                        |   4 -
 tools/rosnode/CHANGELOG.rst                        |   9 +
 tools/rosnode/package.xml                          |   2 +-
 ...d_online.py => check_rosnode_command_online.py} |   0
 tools/rosnode/test/rosnode.test                    |   2 +-
 tools/rosnode/test/setup.cfg                       |   3 -
 tools/rosout/CHANGELOG.rst                         |   9 +
 tools/rosout/CMakeLists.txt                        |   5 +
 tools/rosout/package.xml                           |   2 +-
 tools/rosparam/CHANGELOG.rst                       |  10 +
 tools/rosparam/package.xml                         |   2 +-
 tools/rosparam/src/rosparam/__init__.py            |  41 +++--
 tools/rosservice/CHANGELOG.rst                     |   9 +
 tools/rosservice/package.xml                       |   2 +-
 tools/rostest/CHANGELOG.rst                        |  13 ++
 tools/rostest/cmake/rostest-extras.cmake.em        |   5 +-
 tools/rostest/package.xml                          |   2 +-
 tools/rostest/src/rostest/__init__.py              |  15 +-
 tools/rostest/test/dotname_cases.py                |  36 ++++
 tools/rostest/test/test_dotname.py                 |  52 ++++++
 tools/rostopic/CHANGELOG.rst                       |  12 ++
 tools/rostopic/package.xml                         |   2 +-
 tools/rostopic/src/rostopic/__init__.py            | 201 +++++++++++++++++----
 ...ne.py => check_rostopic_command_line_online.py} |   4 +
 tools/rostopic/test/rostopic.test                  |   2 +-
 tools/rostopic/test/setup.cfg                      |   5 -
 tools/rostopic/test/test_rostopic.py               |   0
 .../test/test_rostopic_command_line_offline.py     |  13 +-
 tools/topic_tools/CHANGELOG.rst                    |  12 ++
 tools/topic_tools/CMakeLists.txt                   |   9 +-
 .../include/topic_tools/shape_shifter.h            |   2 +-
 tools/topic_tools/package.xml                      |   2 +-
 tools/topic_tools/scripts/relay_field              |  10 +-
 tools/topic_tools/src/demux.cpp                    |   3 +
 tools/topic_tools/src/mux.cpp                      |   3 +
 utilities/message_filters/CHANGELOG.rst            |  12 ++
 utilities/message_filters/CMakeLists.txt           |   5 +
 utilities/message_filters/conf.py                  |   4 +-
 .../include/message_filters/chain.h                |   6 +-
 .../include/message_filters/null_types.h           |   4 +-
 .../include/message_filters/subscriber.h           |   2 +
 utilities/message_filters/package.xml              |   2 +-
 .../src/message_filters/__init__.py                |   7 +-
 .../message_filters/test/msg_cache_unittest.cpp    |   2 +-
 .../test/test_approximate_time_policy.cpp          |   6 +-
 utilities/message_filters/test/test_chain.cpp      |  46 ++---
 .../test/test_exact_time_policy.cpp                |  14 +-
 utilities/message_filters/test/test_simple.cpp     |  20 +-
 utilities/message_filters/test/test_subscriber.cpp |   8 +-
 .../message_filters/test/test_synchronizer.cpp     |  20 +-
 .../test/time_sequencer_unittest.cpp               |   4 +-
 .../test/time_synchronizer_unittest.cpp            |  32 ++--
 utilities/roslz4/CHANGELOG.rst                     |  10 +
 utilities/roslz4/CMakeLists.txt                    |   4 +
 utilities/roslz4/package.xml                       |   2 +-
 utilities/roslz4/test/roslz4_test.cpp              |  10 +-
 utilities/roswtf/CHANGELOG.rst                     |   9 +
 utilities/roswtf/CMakeLists.txt                    |   4 +-
 utilities/roswtf/package.xml                       |   2 +-
 utilities/roswtf/src/roswtf/py_pip_deb_checks.py   |   8 +-
 ...line.py => check_roswtf_command_line_online.py} |   0
 utilities/roswtf/test/roswtf.test                  |   2 +-
 utilities/roswtf/test/setup.cfg                    |   3 -
 utilities/xmlrpcpp/CHANGELOG.rst                   |   9 +
 utilities/xmlrpcpp/CMakeLists.txt                  |   5 +
 utilities/xmlrpcpp/package.xml                     |   2 +-
 utilities/xmlrpcpp/src/XmlRpcSocket.cpp            |   3 -
 221 files changed, 1440 insertions(+), 629 deletions(-)

diff --git a/.travis.yml b/.travis.yml
deleted file mode 100644
index f3d9e58..0000000
--- a/.travis.yml
+++ /dev/null
@@ -1,37 +0,0 @@
-language:
-  - cpp
-  - python
-python:
-  - "2.7"
-compiler:
-  - gcc
-  - clang
-# command to install dependencies
-install:
-  - sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu precise main" > /etc/apt/sources.list.d/ros-latest.list'
-  - wget http://packages.ros.org/ros.key -O - | sudo apt-key add -
-  - sudo apt-get update -qq
-  - sudo apt-get install python-rosdep python-catkin-pkg python-nose python-coverage python-wstool pep8 -qq
-  - sudo apt-get install ros-groovy-catkin -qq
-  - sudo rosdep init
-  - rosdep update
-  # Make a workspace
-  - mkdir -p /tmp/ros_comm_ws/src
-  # Add this folder to the workspace
-  - ln -s `pwd` /tmp/ros_comm_ws/src/ros_comm
-  # Install dependencies
-  - cd /tmp/ros_comm_ws
-  - rosdep install --from-paths src --ignore-src --rosdistro groovy -y > /dev/null
-# command to run tests
-script:
-  - source /opt/ros/groovy/setup.bash
-  - cd /tmp/ros_comm_ws
-  - catkin_make tests > log.make_tests
-  - cd build
-  # Manually invoke make, catkin_make
-  - make run_tests > log.run_tests || cat log.*
-  # Check test results
-  - 'python -c "from catkin.test_results import test_results;import sys;sys.exit(sum([v[1] + v[2] for k, v in test_results(\"test_results\").items()]))" || cat log*'
-  - 'python -c "from catkin.test_results import test_results;import sys;sys.exit(sum([v[1] + v[2] for k, v in test_results(\"test_results\").items()]))"'
-notifications:
-  email: false
diff --git a/clients/roscpp/CHANGELOG.rst b/clients/roscpp/CHANGELOG.rst
index ed1698e..ad4a20c 100644
--- a/clients/roscpp/CHANGELOG.rst
+++ b/clients/roscpp/CHANGELOG.rst
@@ -2,6 +2,23 @@
 Changelog for package roscpp
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.12.0 (2016-03-18)
+-------------------
+* improve TopicManager::instance (`#770 <https://github.com/ros/ros_comm/issues/770>`_)
+* change return value of param() to bool (`#753 <https://github.com/ros/ros_comm/issues/753>`_)
+
+1.11.18 (2016-03-17)
+--------------------
+* fix CMake warning about non-existing targets
+
+1.11.17 (2016-03-11)
+--------------------
+* fix order of argument in SubscriberLink interface to match actual implemenation (`#701 <https://github.com/ros/ros_comm/issues/701>`_)
+* add method for getting all the parameters from the parameter server as implemented in the rospy client (`#739 <https://github.com/ros/ros_comm/issues/739>`_)
+* use boost::make_shared instead of new for constructing boost::shared_ptr (`#740 <https://github.com/ros/ros_comm/issues/740>`_)
+* fix max elements param for statistics window (`#750 <https://github.com/ros/ros_comm/issues/750>`_)
+* improve NodeHandle constructor documentation (`#692 <https://github.com/ros/ros_comm/issues/692>`_)
+
 1.11.16 (2015-11-09)
 --------------------
 * add getROSArg function (`#694 <https://github.com/ros/ros_comm/pull/694>`_)
diff --git a/clients/roscpp/CMakeLists.txt b/clients/roscpp/CMakeLists.txt
index 252d43f..c194a56 100644
--- a/clients/roscpp/CMakeLists.txt
+++ b/clients/roscpp/CMakeLists.txt
@@ -1,6 +1,10 @@
 cmake_minimum_required(VERSION 2.8.3)
 project(roscpp)
 
+if(NOT WIN32)
+  set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11 -Wall -Wextra")
+endif()
+
 find_package(catkin REQUIRED COMPONENTS
   cpp_common message_generation rosconsole roscpp_serialization roscpp_traits rosgraph_msgs rostime std_msgs xmlrpcpp
 )
@@ -116,7 +120,7 @@ add_library(roscpp
   src/libros/this_node.cpp
   )
 
-add_dependencies(roscpp roscpp_gencpp rosgraph_msgs_gencpp std_msgs_gencpp)
+add_dependencies(roscpp ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
 
 target_link_libraries(roscpp
   ${catkin_LIBRARIES}
diff --git a/clients/roscpp/include/ros/advertise_service_options.h b/clients/roscpp/include/ros/advertise_service_options.h
index daadc15..e0321ad 100644
--- a/clients/roscpp/include/ros/advertise_service_options.h
+++ b/clients/roscpp/include/ros/advertise_service_options.h
@@ -72,7 +72,7 @@ struct ROSCPP_DECL AdvertiseServiceOptions
     datatype = st::datatype<MReq>();
     req_datatype = mt::datatype<MReq>();
     res_datatype = mt::datatype<MRes>();
-    helper = ServiceCallbackHelperPtr(new ServiceCallbackHelperT<ServiceSpec<MReq, MRes> >(_callback));
+    helper = boost::make_shared<ServiceCallbackHelperT<ServiceSpec<MReq, MRes> > >(_callback);
   }
 
   /**
@@ -92,7 +92,7 @@ struct ROSCPP_DECL AdvertiseServiceOptions
     datatype = st::datatype<Service>();
     req_datatype = mt::datatype<Request>();
     res_datatype = mt::datatype<Response>();
-    helper = ServiceCallbackHelperPtr(new ServiceCallbackHelperT<ServiceSpec<Request, Response> >(_callback));
+    helper = boost::make_shared<ServiceCallbackHelperT<ServiceSpec<Request, Response> > >(_callback);
   }
 
   /**
@@ -112,7 +112,7 @@ struct ROSCPP_DECL AdvertiseServiceOptions
     datatype = st::datatype<Request>();
     req_datatype = mt::datatype<Request>();
     res_datatype = mt::datatype<Response>();
-    helper = ServiceCallbackHelperPtr(new ServiceCallbackHelperT<Spec>(_callback));
+    helper = boost::make_shared<ServiceCallbackHelperT<Spec> >(_callback);
   }
 
   std::string service;                                                ///< Service name
diff --git a/clients/roscpp/include/ros/forwards.h b/clients/roscpp/include/ros/forwards.h
index 71286e6..9095ce5 100644
--- a/clients/roscpp/include/ros/forwards.h
+++ b/clients/roscpp/include/ros/forwards.h
@@ -35,6 +35,7 @@
 #include <list>
 
 #include <boost/shared_ptr.hpp>
+#include <boost/make_shared.hpp>
 #include <boost/weak_ptr.hpp>
 #include <boost/function.hpp>
 
diff --git a/clients/roscpp/include/ros/node_handle.h b/clients/roscpp/include/ros/node_handle.h
index b765c62..4f4c1df 100644
--- a/clients/roscpp/include/ros/node_handle.h
+++ b/clients/roscpp/include/ros/node_handle.h
@@ -112,11 +112,17 @@ namespace ros
     /**
      * \brief Parent constructor
      *
-     * This version of the constructor takes a "parent" NodeHandle, and is equivalent to:
+     * This version of the constructor takes a "parent" NodeHandle.
+     * If the passed "ns" is relative (does not start with a slash), it is equivalent to calling:
      \verbatim
      NodeHandle child(parent.getNamespace() + "/" + ns);
      \endverbatim
      *
+     * If the passed "ns" is absolute (does start with a slash), it is equivalent to calling:
+     \verbatim
+     NodeHandle child(ns);
+     \endverbatim
+     *
      * When a NodeHandle is copied, it inherits the namespace of the
      * NodeHandle being copied, and increments the reference count of
      * the global node state by 1.
@@ -128,11 +134,17 @@ namespace ros
     /**
      * \brief Parent constructor
      *
-     * This version of the constructor takes a "parent" NodeHandle, and is equivalent to:
+     * This version of the constructor takes a "parent" NodeHandle.
+     * If the passed "ns" is relative (does not start with a slash), it is equivalent to calling:
      \verbatim
      NodeHandle child(parent.getNamespace() + "/" + ns, remappings);
      \endverbatim
      *
+     * If the passed "ns" is absolute (does start with a slash), it is equivalent to calling:
+     \verbatim
+     NodeHandle child(ns, remappings);
+     \endverbatim
+     *
      * This version also lets you pass in name remappings that are specific to this NodeHandle
      *
      * When a NodeHandle is copied, it inherits the namespace of the NodeHandle being copied, 
@@ -375,7 +387,7 @@ ros::Subscriber sub = handle.subscribe("my_topic", 1, &Foo::callback, &foo_objec
 \verbatim
 ros::NodeHandle nodeHandle;
 void Foo::callback(const std_msgs::Empty::ConstPtr& message) {}
-boost::shared_ptr<Foo> foo_object(new Foo);
+boost::shared_ptr<Foo> foo_object(boost::make_shared<Foo>());
 ros::Subscriber sub = nodeHandle.subscribe("my_topic", 1, &Foo::callback, foo_object);
 if (sub)  // Enter if subscriber is valid
 {
@@ -438,7 +450,7 @@ ros::Subscriber sub = handle.subscribe("my_topic", 1, &Foo::callback, &foo_objec
 \verbatim
 ros::NodeHandle nodeHandle;
 void Foo::callback(const std_msgs::Empty::ConstPtr& message) {}
-boost::shared_ptr<Foo> foo_object(new Foo);
+boost::shared_ptr<Foo> foo_object(boost::make_shared<Foo>());
 ros::Subscriber sub = nodeHandle.subscribe("my_topic", 1, &Foo::callback, foo_object);
 if (sub)  // Enter if subscriber is valid
 {
@@ -484,7 +496,7 @@ void Foo::callback(const std_msgs::Empty::ConstPtr& message)
 {
 }
 
-boost::shared_ptr<Foo> foo_object(new Foo);
+boost::shared_ptr<Foo> foo_object(boost::make_shared<Foo>());
 ros::Subscriber sub = handle.subscribe("my_topic", 1, &Foo::callback, foo_object);
 \endverbatim
    *
@@ -502,7 +514,7 @@ ros::Subscriber sub = handle.subscribe("my_topic", 1, &Foo::callback, foo_object
 \verbatim
 ros::NodeHandle nodeHandle;
 void Foo::callback(const std_msgs::Empty::ConstPtr& message) {}
-boost::shared_ptr<Foo> foo_object(new Foo);
+boost::shared_ptr<Foo> foo_object(boost::make_shared<Foo>());
 ros::Subscriber sub = nodeHandle.subscribe("my_topic", 1, &Foo::callback, foo_object);
 if (sub)  // Enter if subscriber is valid
 {
@@ -549,7 +561,7 @@ void Foo::callback(const std_msgs::Empty::ConstPtr& message)
 {
 }
 
-boost::shared_ptr<Foo> foo_object(new Foo);
+boost::shared_ptr<Foo> foo_object(boost::make_shared<Foo>());
 ros::Subscriber sub = handle.subscribe("my_topic", 1, &Foo::callback, foo_object);
 \endverbatim
    *
@@ -567,7 +579,7 @@ ros::Subscriber sub = handle.subscribe("my_topic", 1, &Foo::callback, foo_object
 \verbatim
 ros::NodeHandle nodeHandle;
 void Foo::callback(const std_msgs::Empty::ConstPtr& message) {}
-boost::shared_ptr<Foo> foo_object(new Foo);
+boost::shared_ptr<Foo> foo_object(boost::make_shared<Foo>());
 ros::Subscriber sub = nodeHandle.subscribe("my_topic", 1, &Foo::callback, foo_object);
 if (sub)  // Enter if subscriber is valid
 {
@@ -928,7 +940,7 @@ bool Foo::callback(std_srvs::Empty& request, std_srvs::Empty& response)
   return true;
 }
 
-boost::shared_ptr<Foo> foo_object(new Foo);
+boost::shared_ptr<Foo> foo_object(boost::make_shared<Foo>());
 ros::ServiceServer service = handle.advertiseService("my_service", &Foo::callback, foo_object);
 \endverbatim
    *
@@ -975,7 +987,7 @@ bool Foo::callback(ros::ServiceEvent<std_srvs::Empty, std_srvs::Empty>& event)
   return true;
 }
 
-boost::shared_ptr<Foo> foo_object(new Foo);
+boost::shared_ptr<Foo> foo_object(boost::make_shared<Foo>());
 ros::ServiceServer service = handle.advertiseService("my_service", &Foo::callback, foo_object);
 \endverbatim
    *
@@ -2005,6 +2017,12 @@ if (service)  // Enter if advertised service is valid
    */
   bool deleteParam(const std::string& key) const;
 
+  /** \brief Get the keys for all the parameters in the parameter server.
+   * \param keys The keys retrieved.
+   * \return true if the query succeeded, false otherwise.
+   */
+  bool getParamNames(std::vector<std::string>& keys) const;
+
   /** \brief Assign value from parameter server, with default.
    *
    * This method tries to retrieve the indicated parameter value from the
@@ -2015,20 +2033,22 @@ if (service)  // Enter if advertised service is valid
    * \param[out] param_val Storage for the retrieved value.
    * \param default_val Value to use if the server doesn't contain this
    * parameter.
+   * \return true if the parameter was retrieved from the server, false otherwise.
    * \throws InvalidNameException If the parameter key begins with a tilde, or is an otherwise invalid graph resource name
    */
   template<typename T>
-  void param(const std::string& param_name, T& param_val, const T& default_val) const
+  bool param(const std::string& param_name, T& param_val, const T& default_val) const
   {
     if (hasParam(param_name))
     {
       if (getParam(param_name, param_val))
       {
-        return;
+        return true;
       }
     }
 
     param_val = default_val;
+    return false;
   }
 
   /**
diff --git a/clients/roscpp/include/ros/param.h b/clients/roscpp/include/ros/param.h
index a015043..cfa7521 100644
--- a/clients/roscpp/include/ros/param.h
+++ b/clients/roscpp/include/ros/param.h
@@ -584,6 +584,13 @@ ROSCPP_DECL bool search(const std::string& ns, const std::string& key, std::stri
  */
 ROSCPP_DECL bool search(const std::string& key, std::string& result);
 
+/**
+ * \brief Get the list of all the parameters in the server
+ * \param keys The vector of all the keys
+ * \return false if the process fails
+ */
+ROSCPP_DECL bool getParamNames(std::vector<std::string>& keys);
+
 /** \brief Assign value from parameter server, with default.
  *
  * This method tries to retrieve the indicated parameter value from the
@@ -594,20 +601,22 @@ ROSCPP_DECL bool search(const std::string& key, std::string& result);
  * \param[out] param_val Storage for the retrieved value.
  * \param default_val Value to use if the server doesn't contain this
  * parameter.
+ * \return true if the parameter was retrieved from the server, false otherwise.
  * \throws InvalidNameException if the key is not a valid graph resource name
  */
 template<typename T>
-void param(const std::string& param_name, T& param_val, const T& default_val)
+bool param(const std::string& param_name, T& param_val, const T& default_val)
 {
   if (has(param_name))
   {
     if (get(param_name, param_val))
     {
-      return;
+      return true;
     }
   }
 
   param_val = default_val;
+  return false;
 }
 
 /**
diff --git a/clients/roscpp/include/ros/service_callback_helper.h b/clients/roscpp/include/ros/service_callback_helper.h
index 20205e4..0378809 100644
--- a/clients/roscpp/include/ros/service_callback_helper.h
+++ b/clients/roscpp/include/ros/service_callback_helper.h
@@ -50,7 +50,7 @@ struct ROSCPP_DECL ServiceCallbackHelperCallParams
 template<typename M>
 inline boost::shared_ptr<M> defaultServiceCreateFunction()
 {
-  return boost::shared_ptr<M>(new M);
+  return boost::make_shared<M>();
 }
 
 template<typename MReq, typename MRes>
diff --git a/clients/roscpp/include/ros/subscribe_options.h b/clients/roscpp/include/ros/subscribe_options.h
index 7e3bc37..52c602b 100644
--- a/clients/roscpp/include/ros/subscribe_options.h
+++ b/clients/roscpp/include/ros/subscribe_options.h
@@ -88,7 +88,7 @@ struct ROSCPP_DECL SubscribeOptions
     queue_size = _queue_size;
     md5sum = message_traits::md5sum<MessageType>();
     datatype = message_traits::datatype<MessageType>();
-    helper = SubscriptionCallbackHelperPtr(new SubscriptionCallbackHelperT<P>(_callback, factory_fn));
+    helper = boost::make_shared<SubscriptionCallbackHelperT<P> >(_callback, factory_fn);
   }
 
   /**
@@ -109,7 +109,7 @@ struct ROSCPP_DECL SubscribeOptions
     queue_size = _queue_size;
     md5sum = message_traits::md5sum<MessageType>();
     datatype = message_traits::datatype<MessageType>();
-    helper = SubscriptionCallbackHelperPtr(new SubscriptionCallbackHelperT<const boost::shared_ptr<MessageType const>&>(_callback, factory_fn));
+    helper = boost::make_shared<SubscriptionCallbackHelperT<const boost::shared_ptr<MessageType const>&> >(_callback, factory_fn);
   }
 
   std::string topic;                                                ///< Topic to subscribe to
diff --git a/clients/roscpp/include/ros/subscriber_link.h b/clients/roscpp/include/ros/subscriber_link.h
index 475d175..f3a4ebc 100644
--- a/clients/roscpp/include/ros/subscriber_link.h
+++ b/clients/roscpp/include/ros/subscriber_link.h
@@ -69,7 +69,7 @@ public:
   /**
    * \brief Queue up a message for publication.  Throws out old messages if we've reached our Publication's max queue size
    */
-  virtual void enqueueMessage(const SerializedMessage& m, bool nocopy, bool ser) = 0;
+  virtual void enqueueMessage(const SerializedMessage& m, bool ser, bool nocopy) = 0;
 
   virtual void drop() = 0;
 
@@ -77,7 +77,7 @@ public:
   virtual std::string getTransportInfo() = 0;
 
   virtual bool isIntraprocess() { return false; }
-  virtual void getPublishTypes(bool& ser, bool& nocopy, const std::type_info& ti) { ser = true; nocopy = false; }
+  virtual void getPublishTypes(bool& ser, bool& nocopy, const std::type_info& ti) { (void)ti; ser = true; nocopy = false; }
 
   const std::string& getMD5Sum();
   const std::string& getDataType();
diff --git a/clients/roscpp/include/ros/timer_manager.h b/clients/roscpp/include/ros/timer_manager.h
index 9b852b8..e5da5fc 100644
--- a/clients/roscpp/include/ros/timer_manager.h
+++ b/clients/roscpp/include/ros/timer_manager.h
@@ -282,7 +282,7 @@ template<class T, class D, class E>
 int32_t TimerManager<T, D, E>::add(const D& period, const boost::function<void(const E&)>& callback, CallbackQueueInterface* callback_queue,
                                    const VoidConstPtr& tracked_object, bool oneshot)
 {
-  TimerInfoPtr info(new TimerInfo);
+  TimerInfoPtr info(boost::make_shared<TimerInfo>());
   info->period = period;
   info->callback = callback;
   info->callback_queue = callback_queue;
@@ -515,7 +515,7 @@ void TimerManager<T, D, E>::threadFunc()
           current = T::now();
 
           //ROS_DEBUG("Scheduling timer callback for timer [%d] of period [%f], [%f] off expected", info->handle, info->period.toSec(), (current - info->next_expected).toSec());
-          CallbackInterfacePtr cb(new TimerQueueCallback(this, info, info->last_expected, info->last_real, info->next_expected));
+          CallbackInterfacePtr cb(boost::make_shared<TimerQueueCallback>(this, info, info->last_expected, info->last_real, info->next_expected));
           info->callback_queue->addCallback(cb, (uint64_t)info.get());
 
           waiting_.pop_front();
diff --git a/clients/roscpp/include/ros/transport/transport.h b/clients/roscpp/include/ros/transport/transport.h
index 8c7ca78..e856358 100644
--- a/clients/roscpp/include/ros/transport/transport.h
+++ b/clients/roscpp/include/ros/transport/transport.h
@@ -129,7 +129,7 @@ public:
   /**
    * \brief Provides an opportunity for transport-specific options to come in through the header
    */
-  virtual void parseHeader(const Header& header) { }
+  virtual void parseHeader(const Header& header) { (void)header; }
 
 protected:
   Callback disconnect_cb_;
diff --git a/clients/roscpp/package.xml b/clients/roscpp/package.xml
index 1cfed19..f5d08a4 100644
--- a/clients/roscpp/package.xml
+++ b/clients/roscpp/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>roscpp</name>
-  <version>1.11.16</version>
+  <version>1.12.0</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/callback_queue.cpp b/clients/roscpp/src/libros/callback_queue.cpp
index aed7c16..f9312f5 100644
--- a/clients/roscpp/src/libros/callback_queue.cpp
+++ b/clients/roscpp/src/libros/callback_queue.cpp
@@ -117,7 +117,7 @@ void CallbackQueue::addCallback(const CallbackInterfacePtr& callback, uint64_t r
     M_IDInfo::iterator it = id_info_.find(removal_id);
     if (it == id_info_.end())
     {
-      IDInfoPtr id_info(new IDInfo);
+      IDInfoPtr id_info(boost::make_shared<IDInfo>());
       id_info->id = removal_id;
       id_info_.insert(std::make_pair(removal_id, id_info));
     }
diff --git a/clients/roscpp/src/libros/connection.cpp b/clients/roscpp/src/libros/connection.cpp
index 8579317..e75fd07 100644
--- a/clients/roscpp/src/libros/connection.cpp
+++ b/clients/roscpp/src/libros/connection.cpp
@@ -442,6 +442,7 @@ void Connection::onHeaderWritten(const ConnectionPtr& conn)
 
 void Connection::onErrorHeaderWritten(const ConnectionPtr& conn)
 {
+  (void)conn;
   drop(HeaderError);
 }
 
diff --git a/clients/roscpp/src/libros/connection_manager.cpp b/clients/roscpp/src/libros/connection_manager.cpp
index 1d0e222..bbba1a6 100644
--- a/clients/roscpp/src/libros/connection_manager.cpp
+++ b/clients/roscpp/src/libros/connection_manager.cpp
@@ -49,7 +49,7 @@ const ConnectionManagerPtr& ConnectionManager::instance()
     boost::mutex::scoped_lock lock(g_connection_manager_mutex);
     if (!g_connection_manager)
     {
-      g_connection_manager.reset(new ConnectionManager);
+      g_connection_manager = boost::make_shared<ConnectionManager>();
     }
   }
 
@@ -73,7 +73,7 @@ void ConnectionManager::start()
 								this));
 
   // Bring up the TCP listener socket
-  tcpserver_transport_ = TransportTCPPtr(new TransportTCP(&poll_manager_->getPollSet()));
+  tcpserver_transport_ = boost::make_shared<TransportTCP>(&poll_manager_->getPollSet());
   if (!tcpserver_transport_->listen(network::getTCPROSPort(), 
 				    MAX_TCPROS_CONN_QUEUE, 
 				    boost::bind(&ConnectionManager::tcprosAcceptConnection, this, _1)))
@@ -83,7 +83,7 @@ void ConnectionManager::start()
   }
 
   // Bring up the UDP listener socket
-  udpserver_transport_ = TransportUDPPtr(new TransportUDP(&poll_manager_->getPollSet()));
+  udpserver_transport_ = boost::make_shared<TransportUDP>(&poll_manager_->getPollSet());
   if (!udpserver_transport_->createIncoming(0, true))
   {
     ROS_FATAL("Listen failed");
@@ -185,7 +185,7 @@ void ConnectionManager::udprosIncomingConnection(const TransportUDPPtr& transpor
   std::string client_uri = ""; // TODO: transport->getClientURI();
   ROSCPP_LOG_DEBUG("UDPROS received a connection from [%s]", client_uri.c_str());
 
-  ConnectionPtr conn(new Connection());
+  ConnectionPtr conn(boost::make_shared<Connection>());
   addConnection(conn);
 
   conn->initialize(transport, true, NULL);
@@ -197,7 +197,7 @@ void ConnectionManager::tcprosAcceptConnection(const TransportTCPPtr& transport)
   std::string client_uri = transport->getClientURI();
   ROSCPP_LOG_DEBUG("TCPROS received a connection from [%s]", client_uri.c_str());
 
-  ConnectionPtr conn(new Connection());
+  ConnectionPtr conn(boost::make_shared<Connection>());
   addConnection(conn);
 
   conn->initialize(transport, true, boost::bind(&ConnectionManager::onConnectionHeaderReceived, this, _1, _2));
@@ -212,7 +212,7 @@ bool ConnectionManager::onConnectionHeaderReceived(const ConnectionPtr& conn, co
     ROSCPP_LOG_DEBUG("Connection: Creating TransportSubscriberLink for topic [%s] connected to [%s]", 
 		     val.c_str(), conn->getRemoteString().c_str());
 
-    TransportSubscriberLinkPtr sub_link(new TransportSubscriberLink());
+    TransportSubscriberLinkPtr sub_link(boost::make_shared<TransportSubscriberLink>());
     sub_link->initialize(conn);
     ret = sub_link->handleHeader(header);
   }
@@ -221,7 +221,7 @@ bool ConnectionManager::onConnectionHeaderReceived(const ConnectionPtr& conn, co
     ROSCPP_LOG_DEBUG("Connection: Creating ServiceClientLink for service [%s] connected to [%s]", 
 		     val.c_str(), conn->getRemoteString().c_str());
 
-    ServiceClientLinkPtr link(new ServiceClientLink());
+    ServiceClientLinkPtr link(boost::make_shared<ServiceClientLink>());
     link->initialize(conn);
     ret = link->handleHeader(header);
   }
diff --git a/clients/roscpp/src/libros/init.cpp b/clients/roscpp/src/libros/init.cpp
index 1435d02..920e665 100644
--- a/clients/roscpp/src/libros/init.cpp
+++ b/clients/roscpp/src/libros/init.cpp
@@ -268,6 +268,7 @@ CallbackQueuePtr getInternalCallbackQueue()
 
 void basicSigintHandler(int sig)
 {
+  (void)sig;
   ros::requestShutdown();
 }
 
diff --git a/clients/roscpp/src/libros/node_handle.cpp b/clients/roscpp/src/libros/node_handle.cpp
index 271b6c4..6673d48 100644
--- a/clients/roscpp/src/libros/node_handle.cpp
+++ b/clients/roscpp/src/libros/node_handle.cpp
@@ -295,8 +295,8 @@ Publisher NodeHandle::advertise(AdvertiseOptions& ops)
     }
   }
 
-  SubscriberCallbacksPtr callbacks(new SubscriberCallbacks(ops.connect_cb, ops.disconnect_cb, 
-							   ops.tracked_object, ops.callback_queue));
+  SubscriberCallbacksPtr callbacks(boost::make_shared<SubscriberCallbacks>(ops.connect_cb, ops.disconnect_cb, 
+                                                                           ops.tracked_object, ops.callback_queue));
 
   if (TopicManager::instance()->advertise(ops, callbacks))
   {
@@ -592,6 +592,11 @@ bool NodeHandle::deleteParam(const std::string& key) const
   return param::del(resolveName(key));
 }
 
+bool NodeHandle::getParamNames(std::vector<std::string>& keys) const
+{
+  return param::getParamNames(keys);
+}
+
 bool NodeHandle::getParam(const std::string& key, XmlRpc::XmlRpcValue& v) const
 {
   return param::get(resolveName(key), v);
diff --git a/clients/roscpp/src/libros/param.cpp b/clients/roscpp/src/libros/param.cpp
index 8c479b3..8858a40 100644
--- a/clients/roscpp/src/libros/param.cpp
+++ b/clients/roscpp/src/libros/param.cpp
@@ -174,6 +174,7 @@ template <class T>
   // into an array type with the given size
   XmlRpc::XmlRpcValue xml_value;
   const XmlRpc::XmlRpcValue::ValueStruct& xml_map = (const XmlRpc::XmlRpcValue::ValueStruct &)(xml_value);
+  (void)xml_map;
 
   // Copy the contents into the XmlRpcValue
   for(typename std::map<std::string, T>::const_iterator it = map.begin(); it != map.end(); ++it) {
@@ -720,6 +721,35 @@ bool getCached(const std::string& key, std::map<std::string, bool>& map)
   return getImpl(key, map, true);
 }
 
+bool getParamNames(std::vector<std::string>& keys)
+{
+  XmlRpc::XmlRpcValue params, result, payload;
+  params[0] = this_node::getName();
+  if (!master::execute("getParamNames", params, result, payload, false)) {
+    return false;
+  }
+  // Make sure it's an array type
+  if (result.getType() != XmlRpc::XmlRpcValue::TypeArray) {
+    return false;
+  }
+  // Make sure it returned 3 elements
+  if (result.size() != 3) {
+    return false;
+  }
+  // Get the actual parameter keys
+  XmlRpc::XmlRpcValue parameters = result[2];
+  // Resize the output
+  keys.resize(parameters.size());
+
+  // Fill the output vector with the answer
+  for (int i = 0; i < parameters.size(); ++i) {
+    if (parameters[i].getType() != XmlRpc::XmlRpcValue::TypeString) {
+      return false;
+    }
+    keys[i] = std::string(parameters[i]);
+  }
+  return true;
+}
 
 bool search(const std::string& key, std::string& result_out)
 {
diff --git a/clients/roscpp/src/libros/publication.cpp b/clients/roscpp/src/libros/publication.cpp
index af5a254..c51edf3 100644
--- a/clients/roscpp/src/libros/publication.cpp
+++ b/clients/roscpp/src/libros/publication.cpp
@@ -113,7 +113,7 @@ void Publication::addCallbacks(const SubscriberCallbacksPtr& callbacks)
     for (; it != end; ++it)
     {
       const SubscriberLinkPtr& sub_link = *it;
-      CallbackInterfacePtr cb(new PeerConnDisconnCallback(callbacks->connect_, sub_link, callbacks->has_tracked_object_, callbacks->tracked_object_));
+      CallbackInterfacePtr cb(boost::make_shared<PeerConnDisconnCallback>(callbacks->connect_, sub_link, callbacks->has_tracked_object_, callbacks->tracked_object_));
       callbacks->callback_queue_->addCallback(cb, (uint64_t)callbacks.get());
     }
   }
@@ -331,7 +331,7 @@ void Publication::peerConnect(const SubscriberLinkPtr& sub_link)
     const SubscriberCallbacksPtr& cbs = *it;
     if (cbs->connect_ && cbs->callback_queue_)
     {
-      CallbackInterfacePtr cb(new PeerConnDisconnCallback(cbs->connect_, sub_link, cbs->has_tracked_object_, cbs->tracked_object_));
+      CallbackInterfacePtr cb(boost::make_shared<PeerConnDisconnCallback>(cbs->connect_, sub_link, cbs->has_tracked_object_, cbs->tracked_object_));
       cbs->callback_queue_->addCallback(cb, (uint64_t)cbs.get());
     }
   }
@@ -346,7 +346,7 @@ void Publication::peerDisconnect(const SubscriberLinkPtr& sub_link)
     const SubscriberCallbacksPtr& cbs = *it;
     if (cbs->disconnect_ && cbs->callback_queue_)
     {
-      CallbackInterfacePtr cb(new PeerConnDisconnCallback(cbs->disconnect_, sub_link, cbs->has_tracked_object_, cbs->tracked_object_));
+      CallbackInterfacePtr cb(boost::make_shared<PeerConnDisconnCallback>(cbs->disconnect_, sub_link, cbs->has_tracked_object_, cbs->tracked_object_));
       cbs->callback_queue_->addCallback(cb, (uint64_t)cbs.get());
     }
   }
diff --git a/clients/roscpp/src/libros/publisher.cpp b/clients/roscpp/src/libros/publisher.cpp
index 59184d1..02cf7f8 100644
--- a/clients/roscpp/src/libros/publisher.cpp
+++ b/clients/roscpp/src/libros/publisher.cpp
@@ -57,12 +57,12 @@ void Publisher::Impl::unadvertise()
 }
 
 Publisher::Publisher(const std::string& topic, const std::string& md5sum, const std::string& datatype, const NodeHandle& node_handle, const SubscriberCallbacksPtr& callbacks)
-: impl_(new Impl)
+: impl_(boost::make_shared<Impl>())
 {
   impl_->topic_ = topic;
   impl_->md5sum_ = md5sum;
   impl_->datatype_ = datatype;
-  impl_->node_handle_ = NodeHandlePtr(new NodeHandle(node_handle));
+  impl_->node_handle_ = boost::make_shared<NodeHandle>(node_handle);
   impl_->callbacks_ = callbacks;
 }
 
diff --git a/clients/roscpp/src/libros/rosout_appender.cpp b/clients/roscpp/src/libros/rosout_appender.cpp
index c0dbe9d..085e753 100644
--- a/clients/roscpp/src/libros/rosout_appender.cpp
+++ b/clients/roscpp/src/libros/rosout_appender.cpp
@@ -51,7 +51,7 @@ ROSOutAppender::ROSOutAppender()
   AdvertiseOptions ops;
   ops.init<rosgraph_msgs::Log>(names::resolve("/rosout"), 0);
   ops.latch = true;
-  SubscriberCallbacksPtr cbs(new SubscriberCallbacks);
+  SubscriberCallbacksPtr cbs(boost::make_shared<SubscriberCallbacks>());
   TopicManager::instance()->advertise(ops, cbs);
 }
 
@@ -74,7 +74,7 @@ const std::string&  ROSOutAppender::getLastError() const
 
 void ROSOutAppender::log(::ros::console::Level level, const char* str, const char* file, const char* function, int line)
 {
-  rosgraph_msgs::LogPtr msg(new rosgraph_msgs::Log);
+  rosgraph_msgs::LogPtr msg(boost::make_shared<rosgraph_msgs::Log>());
 
   msg->header.stamp = ros::Time::now();
   if (level == ros::console::levels::Debug)
diff --git a/clients/roscpp/src/libros/service.cpp b/clients/roscpp/src/libros/service.cpp
index e748cbd..c1efc4e 100644
--- a/clients/roscpp/src/libros/service.cpp
+++ b/clients/roscpp/src/libros/service.cpp
@@ -47,7 +47,7 @@ bool service::exists(const std::string& service_name, bool print_failure_reason)
 
   if (ServiceManager::instance()->lookupService(mapped_name, host, port))
   {
-    TransportTCPPtr transport(new TransportTCP(0, TransportTCP::SYNCHRONOUS));
+    TransportTCPPtr transport(boost::make_shared<TransportTCP>(static_cast<ros::PollSet*>(NULL), TransportTCP::SYNCHRONOUS));
 
     if (transport->connect(host, port))
     {
diff --git a/clients/roscpp/src/libros/service_client_link.cpp b/clients/roscpp/src/libros/service_client_link.cpp
index 14df4de..7ea4638 100644
--- a/clients/roscpp/src/libros/service_client_link.cpp
+++ b/clients/roscpp/src/libros/service_client_link.cpp
@@ -172,6 +172,7 @@ void ServiceClientLink::onConnectionDropped(const ConnectionPtr& conn)
 
 void ServiceClientLink::onHeaderWritten(const ConnectionPtr& conn)
 {
+  (void)conn;
   connection_->read(4, boost::bind(&ServiceClientLink::onRequestLength, this, _1, _2, _3, _4));
 }
 
@@ -231,6 +232,7 @@ void ServiceClientLink::onResponseWritten(const ConnectionPtr& conn)
 
 void ServiceClientLink::processResponse(bool ok, const SerializedMessage& res)
 {
+  (void)ok;
   connection_->write(res.buf, res.num_bytes, boost::bind(&ServiceClientLink::onResponseWritten, this, _1));
 }
 
diff --git a/clients/roscpp/src/libros/service_manager.cpp b/clients/roscpp/src/libros/service_manager.cpp
index 1f3f4bb..09f6f3d 100644
--- a/clients/roscpp/src/libros/service_manager.cpp
+++ b/clients/roscpp/src/libros/service_manager.cpp
@@ -61,7 +61,7 @@ const ServiceManagerPtr& ServiceManager::instance()
     boost::mutex::scoped_lock lock(g_service_manager_mutex);
     if (!g_service_manager)
     {
-      g_service_manager.reset(new ServiceManager);
+      g_service_manager = boost::make_shared<ServiceManager>();
     }
   }
 
@@ -148,7 +148,7 @@ bool ServiceManager::advertiseService(const AdvertiseServiceOptions& ops)
       return false;
     }
 
-    ServicePublicationPtr pub(new ServicePublication(ops.service, ops.md5sum, ops.datatype, ops.req_datatype, ops.res_datatype, ops.helper, ops.callback_queue, ops.tracked_object));
+    ServicePublicationPtr pub(boost::make_shared<ServicePublication>(ops.service, ops.md5sum, ops.datatype, ops.req_datatype, ops.res_datatype, ops.helper, ops.callback_queue, ops.tracked_object));
     service_publications_.push_back(pub);
   }
 
@@ -262,17 +262,17 @@ ServiceServerLinkPtr ServiceManager::createServiceServerLink(const std::string&
     return ServiceServerLinkPtr();
   }
 
-  TransportTCPPtr transport(new TransportTCP(&poll_manager_->getPollSet()));
+  TransportTCPPtr transport(boost::make_shared<TransportTCP>(&poll_manager_->getPollSet()));
 
   // Make sure to initialize the connection *before* transport->connect()
   // is called, otherwise we might miss a connect error (see #434).
-  ConnectionPtr connection(new Connection());
+  ConnectionPtr connection(boost::make_shared<Connection>());
   connection_manager_->addConnection(connection);
   connection->initialize(transport, false, HeaderReceivedFunc());
 
   if (transport->connect(serv_host, serv_port))
   {
-    ServiceServerLinkPtr client(new ServiceServerLink(service, persistent, request_md5sum, response_md5sum, header_values));
+    ServiceServerLinkPtr client(boost::make_shared<ServiceServerLink>(service, persistent, request_md5sum, response_md5sum, header_values));
 
     {
       boost::mutex::scoped_lock lock(service_server_links_mutex_);
diff --git a/clients/roscpp/src/libros/service_publication.cpp b/clients/roscpp/src/libros/service_publication.cpp
index b64aae3..624ffef 100644
--- a/clients/roscpp/src/libros/service_publication.cpp
+++ b/clients/roscpp/src/libros/service_publication.cpp
@@ -157,7 +157,7 @@ private:
 
 void ServicePublication::processRequest(boost::shared_array<uint8_t> buf, size_t num_bytes, const ServiceClientLinkPtr& link)
 {
-  CallbackInterfacePtr cb(new ServiceCallback(helper_, buf, num_bytes, link, has_tracked_object_, tracked_object_));
+  CallbackInterfacePtr cb(boost::make_shared<ServiceCallback>(helper_, buf, num_bytes, link, has_tracked_object_, tracked_object_));
   callback_queue_->addCallback(cb, (uint64_t)this);
 }
 
diff --git a/clients/roscpp/src/libros/service_server.cpp b/clients/roscpp/src/libros/service_server.cpp
index 563650e..812ff29 100644
--- a/clients/roscpp/src/libros/service_server.cpp
+++ b/clients/roscpp/src/libros/service_server.cpp
@@ -56,10 +56,10 @@ void ServiceServer::Impl::unadvertise()
 }
 
 ServiceServer::ServiceServer(const std::string& service, const NodeHandle& node_handle)
-: impl_(new Impl)
+: impl_(boost::make_shared<Impl>())
 {
   impl_->service_ = service;
-  impl_->node_handle_ = NodeHandlePtr(new NodeHandle(node_handle));
+  impl_->node_handle_ = boost::make_shared<NodeHandle>(node_handle);
 }
 
 ServiceServer::ServiceServer(const ServiceServer& rhs)
diff --git a/clients/roscpp/src/libros/service_server_link.cpp b/clients/roscpp/src/libros/service_server_link.cpp
index 48aa70a..593d6fc 100644
--- a/clients/roscpp/src/libros/service_server_link.cpp
+++ b/clients/roscpp/src/libros/service_server_link.cpp
@@ -131,11 +131,13 @@ bool ServiceServerLink::initialize(const ConnectionPtr& connection)
 
 void ServiceServerLink::onHeaderWritten(const ConnectionPtr& conn)
 {
+  (void)conn;
   header_written_ = true;
 }
 
 bool ServiceServerLink::onHeaderReceived(const ConnectionPtr& conn, const Header& header)
 {
+  (void)conn;
   std::string md5sum, type;
   if (!header.getValue("md5sum", md5sum))
   {
@@ -177,6 +179,7 @@ void ServiceServerLink::onConnectionDropped(const ConnectionPtr& conn)
 
 void ServiceServerLink::onRequestWritten(const ConnectionPtr& conn)
 {
+  (void)conn;
   //ros::WallDuration(0.1).sleep();
   connection_->read(5, boost::bind(&ServiceServerLink::onResponseOkAndLength, this, _1, _2, _3, _4));
 }
@@ -323,7 +326,7 @@ void ServiceServerLink::processNextCall()
 
 bool ServiceServerLink::call(const SerializedMessage& req, SerializedMessage& resp)
 {
-  CallInfoPtr info(new CallInfo);
+  CallInfoPtr info(boost::make_shared<CallInfo>());
   info->req_ = req;
   info->resp_ = &resp;
   info->success_ = false;
diff --git a/clients/roscpp/src/libros/statistics.cpp b/clients/roscpp/src/libros/statistics.cpp
index 634bc80..2b5811e 100644
--- a/clients/roscpp/src/libros/statistics.cpp
+++ b/clients/roscpp/src/libros/statistics.cpp
@@ -45,7 +45,7 @@ void StatisticsLogger::init(const SubscriptionCallbackHelperPtr& helper) {
   hasHeader_ = helper->hasHeader();
   param::param("/enable_statistics", enable_statistics, false);
   param::param("/statistics_window_min_elements", min_elements, 10);
-  param::param("/statistics_window_max_elements", min_elements, 100);
+  param::param("/statistics_window_max_elements", max_elements, 100);
   param::param("/statistics_window_min_size", min_window, 4);
   param::param("/statistics_window_max_size", max_window, 64);
 }
@@ -54,6 +54,7 @@ void StatisticsLogger::callback(const boost::shared_ptr<M_string>& connection_he
                                 const std::string& topic, const std::string& callerid, const SerializedMessage& m, const uint64_t& bytes_sent,
                                 const ros::Time& received_time, bool dropped)
 {
+  (void)connection_header;
   struct StatData stats;
 
   if (!enable_statistics)
@@ -232,11 +233,11 @@ void StatisticsLogger::callback(const boost::shared_ptr<M_string>& connection_he
     pub_.publish(msg);
 
     // dynamic window resizing
-    if (stats.arrival_time_list.size() > max_elements && pub_frequency_ * 2 <= max_window)
+    if (stats.arrival_time_list.size() > static_cast<size_t>(max_elements) && pub_frequency_ * 2 <= max_window)
     {
       pub_frequency_ *= 2;
     }
-    if (stats.arrival_time_list.size() < min_elements && pub_frequency_ / 2 >= min_window)
+    if (stats.arrival_time_list.size() < static_cast<size_t>(min_elements) && pub_frequency_ / 2 >= min_window)
     {
       pub_frequency_ /= 2;
     }
diff --git a/clients/roscpp/src/libros/subscriber.cpp b/clients/roscpp/src/libros/subscriber.cpp
index 00da0f4..5710e84 100644
--- a/clients/roscpp/src/libros/subscriber.cpp
+++ b/clients/roscpp/src/libros/subscriber.cpp
@@ -60,10 +60,10 @@ namespace ros
 
   Subscriber::Subscriber(const std::string& topic, const NodeHandle& node_handle, 
 			 const SubscriptionCallbackHelperPtr& helper)
-  : impl_(new Impl)
+  : impl_(boost::make_shared<Impl>())
   {
     impl_->topic_ = topic;
-    impl_->node_handle_ = NodeHandlePtr(new NodeHandle(node_handle));
+    impl_->node_handle_ = boost::make_shared<NodeHandle>(node_handle);
     impl_->helper_ = helper;
   }
 
diff --git a/clients/roscpp/src/libros/subscription.cpp b/clients/roscpp/src/libros/subscription.cpp
index 194e759..d2163d7 100644
--- a/clients/roscpp/src/libros/subscription.cpp
+++ b/clients/roscpp/src/libros/subscription.cpp
@@ -185,8 +185,8 @@ void Subscription::addLocalConnection(const PublicationPtr& pub)
 
   ROSCPP_LOG_DEBUG("Creating intraprocess link for topic [%s]", name_.c_str());
 
-  IntraProcessPublisherLinkPtr pub_link(new IntraProcessPublisherLink(shared_from_this(), XMLRPCManager::instance()->getServerURI(), transport_hints_));
-  IntraProcessSubscriberLinkPtr sub_link(new IntraProcessSubscriberLink(pub));
+  IntraProcessPublisherLinkPtr pub_link(boost::make_shared<IntraProcessPublisherLink>(shared_from_this(), XMLRPCManager::instance()->getServerURI(), transport_hints_));
+  IntraProcessSubscriberLinkPtr sub_link(boost::make_shared<IntraProcessSubscriberLink>(pub));
   pub_link->setPublisher(sub_link);
   sub_link->setSubscriber(pub_link);
 
@@ -355,7 +355,7 @@ bool Subscription::negotiateConnection(const std::string& xmlrpc_uri)
     if (*it == "UDP")
     {
       int max_datagram_size = transport_hints_.getMaxDatagramSize();
-      udp_transport = TransportUDPPtr(new TransportUDP(&PollManager::instance()->getPollSet()));
+      udp_transport = boost::make_shared<TransportUDP>(&PollManager::instance()->getPollSet());
       if (!max_datagram_size)
         max_datagram_size = udp_transport->getMaxDatagramSize();
       udp_transport->createIncoming(0, false);
@@ -419,7 +419,7 @@ bool Subscription::negotiateConnection(const std::string& xmlrpc_uri)
 
   // The PendingConnectionPtr takes ownership of c, and will delete it on
   // destruction.
-  PendingConnectionPtr conn(new PendingConnection(c, udp_transport, shared_from_this(), xmlrpc_uri));
+  PendingConnectionPtr conn(boost::make_shared<PendingConnection>(c, udp_transport, shared_from_this(), xmlrpc_uri));
 
   XMLRPCManager::instance()->addASyncConnection(conn);
   // Put this connection on the list that we'll look at later.
@@ -505,11 +505,11 @@ void Subscription::pendingConnectionDone(const PendingConnectionPtr& conn, XmlRp
     int pub_port = proto[2];
     ROSCPP_LOG_DEBUG("Connecting via tcpros to topic [%s] at host [%s:%d]", name_.c_str(), pub_host.c_str(), pub_port);
 
-    TransportTCPPtr transport(new TransportTCP(&PollManager::instance()->getPollSet()));
+    TransportTCPPtr transport(boost::make_shared<TransportTCP>(&PollManager::instance()->getPollSet()));
     if (transport->connect(pub_host, pub_port))
     {
-      ConnectionPtr connection(new Connection());
-      TransportPublisherLinkPtr pub_link(new TransportPublisherLink(shared_from_this(), xmlrpc_uri, transport_hints_));
+      ConnectionPtr connection(boost::make_shared<Connection>());
+      TransportPublisherLinkPtr pub_link(boost::make_shared<TransportPublisherLink>(shared_from_this(), xmlrpc_uri, transport_hints_));
 
       connection->initialize(transport, false, HeaderReceivedFunc());
       pub_link->initialize(connection);
@@ -545,7 +545,7 @@ void Subscription::pendingConnectionDone(const PendingConnectionPtr& conn, XmlRp
     int conn_id = proto[3];
     int max_datagram_size = proto[4];
     std::vector<char> header_bytes = proto[5];
-    boost::shared_array<uint8_t> buffer = boost::shared_array<uint8_t>(new uint8_t[header_bytes.size()]);
+    boost::shared_array<uint8_t> buffer(new uint8_t[header_bytes.size()]);
     memcpy(buffer.get(), &header_bytes[0], header_bytes.size());
     Header h;
     std::string err;
@@ -565,10 +565,10 @@ void Subscription::pendingConnectionDone(const PendingConnectionPtr& conn, XmlRp
       return;
     }
 
-    TransportPublisherLinkPtr pub_link(new TransportPublisherLink(shared_from_this(), xmlrpc_uri, transport_hints_));
+    TransportPublisherLinkPtr pub_link(boost::make_shared<TransportPublisherLink>(shared_from_this(), xmlrpc_uri, transport_hints_));
     if (pub_link->setHeader(h))
     {
-      ConnectionPtr connection(new Connection());
+      ConnectionPtr connection(boost::make_shared<Connection>());
       connection->initialize(udp_transport, false, NULL);
       connection->setHeader(h);
       pub_link->initialize(connection);
@@ -700,10 +700,10 @@ bool Subscription::addCallback(const SubscriptionCallbackHelperPtr& helper, cons
   {
     boost::mutex::scoped_lock lock(callbacks_mutex_);
 
-    CallbackInfoPtr info(new CallbackInfo);
+    CallbackInfoPtr info(boost::make_shared<CallbackInfo>());
     info->helper_ = helper;
     info->callback_queue_ = queue;
-    info->subscription_queue_.reset(new SubscriptionQueue(name_, queue_size, allow_concurrent_callbacks));
+    info->subscription_queue_ = boost::make_shared<SubscriptionQueue>(name_, queue_size, allow_concurrent_callbacks);
     info->tracked_object_ = tracked_object;
     info->has_tracked_object_ = false;
     if (tracked_object)
@@ -736,7 +736,7 @@ bool Subscription::addCallback(const SubscriptionCallbackHelperPtr& helper, cons
           {
             const LatchInfo& latch_info = des_it->second;
 
-            MessageDeserializerPtr des(new MessageDeserializer(helper, latch_info.message, latch_info.connection_header));
+            MessageDeserializerPtr des(boost::make_shared<MessageDeserializer>(helper, latch_info.message, latch_info.connection_header));
             bool was_full = false;
             info->subscription_queue_->push(info->helper_, des, info->has_tracked_object_, info->tracked_object_, true, latch_info.receipt_time, &was_full);
             if (!was_full)
@@ -784,6 +784,7 @@ void Subscription::removeCallback(const SubscriptionCallbackHelperPtr& helper)
 
 void Subscription::headerReceived(const PublisherLinkPtr& link, const Header& h)
 {
+  (void)h;
   boost::mutex::scoped_lock lock(md5sum_mutex_);
   if (md5sum_ == "*")
   {
diff --git a/clients/roscpp/src/libros/topic_manager.cpp b/clients/roscpp/src/libros/topic_manager.cpp
index a11fd81..0142cda 100644
--- a/clients/roscpp/src/libros/topic_manager.cpp
+++ b/clients/roscpp/src/libros/topic_manager.cpp
@@ -53,20 +53,10 @@ using namespace std; // sigh
 namespace ros
 {
 
-TopicManagerPtr g_topic_manager;
-boost::mutex g_topic_manager_mutex;
 const TopicManagerPtr& TopicManager::instance()
 {
-  if (!g_topic_manager)
-  {
-    boost::mutex::scoped_lock lock(g_topic_manager_mutex);
-    if (!g_topic_manager)
-    {
-      g_topic_manager.reset(new TopicManager);
-    }
-  }
-
-  return g_topic_manager;
+  static TopicManagerPtr topic_manager = boost::make_shared<TopicManager>();
+  return topic_manager;
 }
 
 TopicManager::TopicManager()
@@ -281,7 +271,7 @@ bool TopicManager::subscribe(const SubscribeOptions& ops)
   const std::string& md5sum = ops.md5sum;
   std::string datatype = ops.datatype;
 
-  SubscriptionPtr s(new Subscription(ops.topic, md5sum, datatype, ops.transport_hints));
+  SubscriptionPtr s(boost::make_shared<Subscription>(ops.topic, md5sum, datatype, ops.transport_hints));
   s->addCallback(ops.helper, ops.md5sum, ops.callback_queue, ops.queue_size, ops.tracked_object, ops.allow_concurrent_callbacks);
 
   if (!registerSubscriber(s, ops.datatype))
@@ -357,7 +347,7 @@ bool TopicManager::advertise(const AdvertiseOptions& ops, const SubscriberCallba
       return true;
     }
 
-    pub = PublicationPtr(new Publication(ops.topic, ops.datatype, ops.md5sum, ops.message_definition, ops.queue_size, ops.latch, ops.has_header));
+    pub = PublicationPtr(boost::make_shared<Publication>(ops.topic, ops.datatype, ops.md5sum, ops.message_definition, ops.queue_size, ops.latch, ops.has_header));
     pub->addCallbacks(callbacks);
     advertised_topics_.push_back(pub);
   }
@@ -635,7 +625,7 @@ bool TopicManager::requestTopic(const string &topic,
         return false;
       }
       std::vector<char> header_bytes = proto[1];
-      boost::shared_array<uint8_t> buffer = boost::shared_array<uint8_t>(new uint8_t[header_bytes.size()]);
+      boost::shared_array<uint8_t> buffer(new uint8_t[header_bytes.size()]);
       memcpy(buffer.get(), &header_bytes[0], header_bytes.size());
       Header h;
       string err;
@@ -1031,6 +1021,7 @@ void TopicManager::requestTopicCallback(XmlRpc::XmlRpcValue& params, XmlRpc::Xml
 
 void TopicManager::getBusStatsCallback(XmlRpc::XmlRpcValue& params, XmlRpc::XmlRpcValue& result)
 {
+  (void)params;
   result[0] = 1;
   result[1] = std::string("");
   XmlRpcValue response;
@@ -1040,6 +1031,7 @@ void TopicManager::getBusStatsCallback(XmlRpc::XmlRpcValue& params, XmlRpc::XmlR
 
 void TopicManager::getBusInfoCallback(XmlRpc::XmlRpcValue& params, XmlRpc::XmlRpcValue& result)
 {
+  (void)params;
   result[0] = 1;
   result[1] = std::string("");
   XmlRpcValue response;
@@ -1049,6 +1041,7 @@ void TopicManager::getBusInfoCallback(XmlRpc::XmlRpcValue& params, XmlRpc::XmlRp
 
 void TopicManager::getSubscriptionsCallback(XmlRpc::XmlRpcValue& params, XmlRpc::XmlRpcValue& result)
 {
+  (void)params;
   result[0] = 1;
   result[1] = std::string("subscriptions");
   XmlRpcValue response;
@@ -1058,6 +1051,7 @@ void TopicManager::getSubscriptionsCallback(XmlRpc::XmlRpcValue& params, XmlRpc:
 
 void TopicManager::getPublicationsCallback(XmlRpc::XmlRpcValue& params, XmlRpc::XmlRpcValue& result)
 {
+  (void)params;
   result[0] = 1;
   result[1] = std::string("publications");
   XmlRpcValue response;
diff --git a/clients/roscpp/src/libros/transport/transport_tcp.cpp b/clients/roscpp/src/libros/transport/transport_tcp.cpp
index 316b788..f061fc2 100644
--- a/clients/roscpp/src/libros/transport/transport_tcp.cpp
+++ b/clients/roscpp/src/libros/transport/transport_tcp.cpp
@@ -626,7 +626,7 @@ TransportTCPPtr TransportTCP::accept()
   {
     ROSCPP_LOG_DEBUG("Accepted connection on socket [%d], new socket [%d]", sock_, new_sock);
 
-    TransportTCPPtr transport(new TransportTCP(poll_set_, flags_));
+    TransportTCPPtr transport(boost::make_shared<TransportTCP>(poll_set_, flags_));
     if (!transport->setSocket(new_sock))
     {
       ROS_ERROR("Failed to set socket on transport for socket %d", new_sock);
diff --git a/clients/roscpp/src/libros/transport/transport_udp.cpp b/clients/roscpp/src/libros/transport/transport_udp.cpp
index 75bf608..848893b 100644
--- a/clients/roscpp/src/libros/transport/transport_udp.cpp
+++ b/clients/roscpp/src/libros/transport/transport_udp.cpp
@@ -686,7 +686,7 @@ TransportUDPPtr TransportUDP::createOutgoing(std::string host, int port, int con
 {
   ROS_ASSERT(is_server_);
   
-  TransportUDPPtr transport(new TransportUDP(poll_set_, flags_, max_datagram_size));
+  TransportUDPPtr transport(boost::make_shared<TransportUDP>(poll_set_, flags_, max_datagram_size));
   if (!transport->connect(host, port, connection_id))
   {
     ROS_ERROR("Failed to create outgoing connection");
diff --git a/clients/roscpp/src/libros/transport_publisher_link.cpp b/clients/roscpp/src/libros/transport_publisher_link.cpp
index 98b1617..d1929f6 100644
--- a/clients/roscpp/src/libros/transport_publisher_link.cpp
+++ b/clients/roscpp/src/libros/transport_publisher_link.cpp
@@ -119,6 +119,7 @@ void TransportPublisherLink::drop()
 
 void TransportPublisherLink::onHeaderWritten(const ConnectionPtr& conn)
 {
+  (void)conn;
   // Do nothing
 }
 
@@ -221,10 +222,10 @@ void TransportPublisherLink::onRetryTimer(const ros::WallTimerEvent&)
 
       ROSCPP_LOG_DEBUG("Retrying connection to [%s:%d] for topic [%s]", host.c_str(), port, topic.c_str());
 
-      TransportTCPPtr transport(new TransportTCP(&PollManager::instance()->getPollSet()));
+      TransportTCPPtr transport(boost::make_shared<TransportTCP>(&PollManager::instance()->getPollSet()));
       if (transport->connect(host, port))
       {
-        ConnectionPtr connection(new Connection);
+        ConnectionPtr connection(boost::make_shared<Connection>());
         connection->initialize(transport, false, HeaderReceivedFunc());
         initialize(connection);
 
diff --git a/clients/roscpp/src/libros/transport_subscriber_link.cpp b/clients/roscpp/src/libros/transport_subscriber_link.cpp
index b26ae75..ace5aa4 100644
--- a/clients/roscpp/src/libros/transport_subscriber_link.cpp
+++ b/clients/roscpp/src/libros/transport_subscriber_link.cpp
@@ -135,12 +135,14 @@ void TransportSubscriberLink::onConnectionDropped(const ConnectionPtr& conn)
 
 void TransportSubscriberLink::onHeaderWritten(const ConnectionPtr& conn)
 {
+  (void)conn;
   header_written_ = true;
   startMessageWrite(true);
 }
 
 void TransportSubscriberLink::onMessageWritten(const ConnectionPtr& conn)
 {
+  (void)conn;
   writing_message_ = false;
   startMessageWrite(true);
 }
@@ -173,6 +175,7 @@ void TransportSubscriberLink::startMessageWrite(bool immediate_write)
 
 void TransportSubscriberLink::enqueueMessage(const SerializedMessage& m, bool ser, bool nocopy)
 {
+  (void)nocopy;
   if (!ser)
   {
     return;
diff --git a/clients/roscpp/src/libros/xmlrpc_manager.cpp b/clients/roscpp/src/libros/xmlrpc_manager.cpp
index e5cd8d1..272315b 100644
--- a/clients/roscpp/src/libros/xmlrpc_manager.cpp
+++ b/clients/roscpp/src/libros/xmlrpc_manager.cpp
@@ -89,6 +89,7 @@ private:
 
 void getPid(const XmlRpcValue& params, XmlRpcValue& result)
 {
+  (void)params;
   result = xmlrpc::responseInt(1, "", (int)getpid());
 }
 
diff --git a/clients/rospy/CHANGELOG.rst b/clients/rospy/CHANGELOG.rst
index 0bdb034..5dc38eb 100644
--- a/clients/rospy/CHANGELOG.rst
+++ b/clients/rospy/CHANGELOG.rst
@@ -2,6 +2,16 @@
 Changelog for package rospy
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.12.0 (2016-03-18)
+-------------------
+
+1.11.18 (2016-03-17)
+--------------------
+
+1.11.17 (2016-03-11)
+--------------------
+* preserve identity of numpy_msg(T) (`#758 <https://github.com/ros/ros_comm/pull/758>`_)
+
 1.11.16 (2015-11-09)
 --------------------
 * catch ROSInterruptException from rospy timers when shutting down (`#690 <https://github.com/ros/ros_comm/pull/690>`_)
diff --git a/clients/rospy/package.xml b/clients/rospy/package.xml
index 8ad6f64..7b8c415 100644
--- a/clients/rospy/package.xml
+++ b/clients/rospy/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>rospy</name>
-  <version>1.11.16</version>
+  <version>1.12.0</version>
   <description>
     rospy is a pure Python client library for ROS. The rospy client
     API enables Python programmers to quickly interface with ROS <a
diff --git a/clients/rospy/src/rospy/core.py b/clients/rospy/src/rospy/core.py
index f094cb4..08affe8 100644
--- a/clients/rospy/src/rospy/core.py
+++ b/clients/rospy/src/rospy/core.py
@@ -156,17 +156,16 @@ logfatal = logging.getLogger('rosout').critical
 MASTER_NAME = "master" #master is a reserved node name for the central master
 
 import warnings
+import functools
 def deprecated(func):
     """This is a decorator which can be used to mark functions
     as deprecated. It will result in a warning being emmitted
     when the function is used."""
+    @functools.wraps(func)
     def newFunc(*args, **kwargs):
         warnings.warn("Call to deprecated function %s." % func.__name__,
                       category=DeprecationWarning, stacklevel=2)
         return func(*args, **kwargs)
-    newFunc.__name__ = func.__name__
-    newFunc.__doc__ = func.__doc__
-    newFunc.__dict__.update(func.__dict__)
     return newFunc
 
 @deprecated
diff --git a/clients/rospy/src/rospy/numpy_msg.py b/clients/rospy/src/rospy/numpy_msg.py
index abc0e17..f312d62 100644
--- a/clients/rospy/src/rospy/numpy_msg.py
+++ b/clients/rospy/src/rospy/numpy_msg.py
@@ -74,12 +74,16 @@ def _deserialize_numpy(self, str):
     # pass in numpy module reference to prevent import in auto-generated code
     return self.deserialize_numpy(str, numpy)
     
+_numpy_msg_types = {}
 ## Use this function to generate message instances using numpy array
 ## types for numerical arrays. 
 ## @msg_type Message class: call this functioning on the message type that you pass
 ## into a Publisher or Subscriber call. 
 ## @returns Message class
 def numpy_msg(msg_type):
+    if msg_type in _numpy_msg_types:
+        return _numpy_msg_types[msg_type]
+
     classdict = { '__slots__': msg_type.__slots__, '_slot_types': msg_type._slot_types,
                   '_md5sum': msg_type._md5sum, '_type': msg_type._type,
                   '_has_header': msg_type._has_header, '_full_text': msg_type._full_text,
@@ -90,4 +94,6 @@ def numpy_msg(msg_type):
 
     # create the numpy message type
     msg_type_name = "Numpy_%s"%msg_type._type.replace('/', '__')
-    return type(msg_type_name,(msg_type,),classdict)
+    numpy_type = type(msg_type_name,(msg_type,),classdict)
+    _numpy_msg_types[msg_type] = numpy_type
+    return numpy_type
diff --git a/clients/rospy/src/rospy/rostime.py b/clients/rospy/src/rospy/rostime.py
index 4471457..0b87179 100644
--- a/clients/rospy/src/rospy/rostime.py
+++ b/clients/rospy/src/rospy/rostime.py
@@ -87,7 +87,7 @@ class Duration(genpy.Duration):
         @param nsecs: nanoseconds
         @type  nsecs: int
         """
-        genpy.Duration.__init__(self, secs, nsecs)
+        super(Duration, self).__init__(secs, nsecs)
 
     def __repr__(self):
         return 'rospy.Duration[%d]' % self.to_nsec()
@@ -135,7 +135,7 @@ class Time(genpy.Time):
         @param nsecs: nanoseconds since seconds (since epoch)
         @type  nsecs: int
         """
-        genpy.Time.__init__(self, secs, nsecs)
+        super(Time, self).__init__(secs, nsecs)
         
     def __repr__(self):
         return 'rospy.Time[%d]' % self.to_nsec()
diff --git a/clients/rospy/src/rospy/timer.py b/clients/rospy/src/rospy/timer.py
index 5b91510..4ddf491 100644
--- a/clients/rospy/src/rospy/timer.py
+++ b/clients/rospy/src/rospy/timer.py
@@ -191,7 +191,7 @@ class Timer(threading.Thread):
         @param oneshot: if True, fire only once, otherwise fire continuously until shutdown is called [default: False]
         @type  oneshot: bool
         """
-        threading.Thread.__init__(self)
+        super(Timer, self).__init__()
         self._period   = period
         self._callback = callback
         self._oneshot  = oneshot
diff --git a/ros_comm/CHANGELOG.rst b/ros_comm/CHANGELOG.rst
index 493b26f..0a35df3 100644
--- a/ros_comm/CHANGELOG.rst
+++ b/ros_comm/CHANGELOG.rst
@@ -2,6 +2,15 @@
 Changelog for package ros_comm
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.12.0 (2016-03-18)
+-------------------
+
+1.11.18 (2016-03-17)
+--------------------
+
+1.11.17 (2016-03-11)
+--------------------
+
 1.11.16 (2015-11-09)
 --------------------
 
diff --git a/ros_comm/package.xml b/ros_comm/package.xml
index 5ac20f2..ee0e7b7 100644
--- a/ros_comm/package.xml
+++ b/ros_comm/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>ros_comm</name>
-  <version>1.11.16</version>
+  <version>1.12.0</version>
   <description>
     ROS communications-related packages, including core client libraries (roscpp, rospy) and graph introspection tools (rostopic, rosnode, rosservice, rosparam).
   </description>
diff --git a/test/test_rosbag/CMakeLists.txt b/test/test_rosbag/CMakeLists.txt
index 1ce81c7..5c8b3ef 100644
--- a/test/test_rosbag/CMakeLists.txt
+++ b/test/test_rosbag/CMakeLists.txt
@@ -1,6 +1,11 @@
 cmake_minimum_required(VERSION 2.8.3)
 
 project(test_rosbag)
+
+if(NOT WIN32)
+  set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -Wextra")
+endif()
+
 find_package(catkin REQUIRED COMPONENTS message_generation rosbag rosconsole roscpp rosgraph_msgs rostest rosunit topic_tools xmlrpcpp)
 
 if(CATKIN_ENABLE_TESTING)
diff --git a/test/test_rosbag/package.xml b/test/test_rosbag/package.xml
index 0d86568..5752ce4 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.16</version>
+  <version>1.12.0</version>
   <description>
     A package containing the unit tests for rosbag.
   </description>
diff --git a/test/test_rosbag/test/test_bag.cpp.in b/test/test_rosbag/test/test_bag.cpp.in
index c26d39d..db4e107 100644
--- a/test/test_rosbag/test/test_bag.cpp.in
+++ b/test/test_rosbag/test/test_bag.cpp.in
@@ -131,8 +131,8 @@ TEST_F(BagTest, different_writes) {
     b1.open(filename, rosbag::bagmode::Write | rosbag::bagmode::Read);
 
     std_msgs::String msg1;
-    std_msgs::String::Ptr msg2 = boost::shared_ptr<std_msgs::String>(new std_msgs::String);
-    std_msgs::String::ConstPtr msg3 = boost::shared_ptr<std_msgs::String const>(new std_msgs::String);
+    std_msgs::String::Ptr msg2 = boost::make_shared<std_msgs::String>();
+    std_msgs::String::ConstPtr msg3 = boost::make_shared<std_msgs::String const>();
     
     rosbag::View view;
     view.addQuery(b1);
diff --git a/test/test_rosbag_storage/package.xml b/test/test_rosbag_storage/package.xml
index 250d5d2..9f0c663 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.16</version>
+  <version>1.12.0</version>
   <description>
     A package containing the unit tests for rosbag_storage.
   </description>
diff --git a/test/test_roscpp/CMakeLists.txt b/test/test_roscpp/CMakeLists.txt
index 88f7b3a..508590e 100644
--- a/test/test_roscpp/CMakeLists.txt
+++ b/test/test_roscpp/CMakeLists.txt
@@ -2,6 +2,10 @@ cmake_minimum_required(VERSION 2.8.3)
 
 project(test_roscpp)
 
+if(NOT WIN32)
+  set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -Wextra")
+endif()
+
 find_package(catkin REQUIRED COMPONENTS
   message_generation roscpp rostest rosunit std_srvs
 )
diff --git a/test/test_roscpp/package.xml b/test/test_roscpp/package.xml
index 006877e..b5352b0 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.16</version>
+  <version>1.12.0</version>
   <description>
     Tests for roscpp which depend on rostest.
   </description>
diff --git a/test/test_roscpp/perf/CMakeLists.txt b/test/test_roscpp/perf/CMakeLists.txt
index 5bb2441..889a017 100644
--- a/test/test_roscpp/perf/CMakeLists.txt
+++ b/test/test_roscpp/perf/CMakeLists.txt
@@ -14,7 +14,7 @@ include_directories(include ${catkin_INCLUDE_DIRS} ${Boost_INCLUDE_DIRS})
 
 #common commands for building c++ executables and libraries
 add_library(${PROJECT_NAME}_perf EXCLUDE_FROM_ALL src/intra.cpp src/inter.cpp)
-add_dependencies(${PROJECT_NAME}_perf ${PROJECT_NAME}_gencpp)
+add_dependencies(${PROJECT_NAME}_perf ${${PROJECT_NAME}_EXPORTED_TARGETS})
 target_link_libraries(${PROJECT_NAME}_perf ${Boost_LIBRARIES} ${catkin_LIBRARIES})
 
 # These performance tests will not be built or executed automatically.
diff --git a/test/test_roscpp/perf/src/intra.cpp b/test/test_roscpp/perf/src/intra.cpp
index f01ec8a..233dc4b 100644
--- a/test/test_roscpp/perf/src/intra.cpp
+++ b/test/test_roscpp/perf/src/intra.cpp
@@ -179,7 +179,7 @@ void ThroughputTest::sendThread(boost::barrier* all_connected)
     }
   }
 
-  test_roscpp::ThroughputMessagePtr msg(new test_roscpp::ThroughputMessage);
+  test_roscpp::ThroughputMessagePtr msg(boost::make_shared<test_roscpp::ThroughputMessage>());
   msg->array.resize(message_size_);
 
   all_connected->wait();
@@ -443,7 +443,7 @@ void LatencyTest::sendThread(boost::barrier* all_connected, uint32_t thread_inde
   std::vector<test_roscpp::LatencyMessagePtr> messages;
   for (uint32_t i = 0; i < streams_; ++i)
   {
-    test_roscpp::LatencyMessagePtr msg(new test_roscpp::LatencyMessage);
+    test_roscpp::LatencyMessagePtr msg(boost::make_shared<test_roscpp::LatencyMessage>());
     msg->thread_index = thread_index;
     msg->array.resize(message_size_);
     messages.push_back(msg);
@@ -670,7 +670,7 @@ STLatencyResult STLatencyTest::run()
 
   ROS_INFO("All connections established");
 
-  test_roscpp::LatencyMessagePtr msg(new test_roscpp::LatencyMessage);
+  test_roscpp::LatencyMessagePtr msg(boost::make_shared<test_roscpp::LatencyMessage>());
   msg->publish_time = ros::WallTime::now().toSec();
   send_pub.publish(msg);
   while (msg->count < message_count_)
diff --git a/test/test_roscpp/perf_serialization/CMakeLists.txt b/test/test_roscpp/perf_serialization/CMakeLists.txt
index 14a0a80..d07e19f 100644
--- a/test/test_roscpp/perf_serialization/CMakeLists.txt
+++ b/test/test_roscpp/perf_serialization/CMakeLists.txt
@@ -3,6 +3,6 @@ target_link_libraries(${PROJECT_NAME}-pointcloud_serdes ${catkin_LIBRARIES})
 if(TARGET tests)
   add_dependencies(tests ${PROJECT_NAME}-pointcloud_serdes) 
 endif()
-add_dependencies(${PROJECT_NAME}-pointcloud_serdes ${PROJECT_NAME}_gencpp) 
+add_dependencies(${PROJECT_NAME}-pointcloud_serdes ${${PROJECT_NAME}_EXPORTED_TARGETS})
 #rosbuild_add_compile_flags(pointcloud_serdes "-O3 -funroll-loops")
 #rosbuild_add_compile_flags(pointcloud_serdes "-march=prescott")
diff --git a/test/test_roscpp/test/src/CMakeLists.txt b/test/test_roscpp/test/src/CMakeLists.txt
index 52100ee..54f086d 100644
--- a/test/test_roscpp/test/src/CMakeLists.txt
+++ b/test/test_roscpp/test/src/CMakeLists.txt
@@ -55,11 +55,11 @@ target_link_libraries(${PROJECT_NAME}-param_update_test ${catkin_LIBRARIES})
 
 add_executable(${PROJECT_NAME}-real_time_test EXCLUDE_FROM_ALL real_time_test.cpp)
 target_link_libraries(${PROJECT_NAME}-real_time_test ${GTEST_LIBRARIES} ${catkin_LIBRARIES})
-add_dependencies(${PROJECT_NAME}-real_time_test rosgraph_msgs_gencpp)
+add_dependencies(${PROJECT_NAME}-real_time_test ${rosgraph_msgs_EXPORTED_TARGETS})
 
 add_executable(${PROJECT_NAME}-sim_time_test EXCLUDE_FROM_ALL sim_time_test.cpp)
 target_link_libraries(${PROJECT_NAME}-sim_time_test ${GTEST_LIBRARIES} ${catkin_LIBRARIES})
-add_dependencies(${PROJECT_NAME}-sim_time_test rosgraph_msgs_gencpp)
+add_dependencies(${PROJECT_NAME}-sim_time_test ${rosgraph_msgs_EXPORTED_TARGETS})
 
 # Call a service
 add_executable(${PROJECT_NAME}-service_adv EXCLUDE_FROM_ALL service_adv.cpp)
@@ -76,14 +76,14 @@ target_link_libraries(${PROJECT_NAME}-service_call_zombie ${GTEST_LIBRARIES} ${c
 
 add_executable(${PROJECT_NAME}-service_deadlock EXCLUDE_FROM_ALL service_deadlock.cpp)
 target_link_libraries(${PROJECT_NAME}-service_deadlock ${GTEST_LIBRARIES} ${catkin_LIBRARIES})
-add_dependencies(${PROJECT_NAME}-service_deadlock std_srvs_gencpp)
+add_dependencies(${PROJECT_NAME}-service_deadlock ${std_srvs_EXPORTED_TARGETS})
 
 add_executable(${PROJECT_NAME}-service_call_repeatedly EXCLUDE_FROM_ALL service_call_repeatedly.cpp)
 target_link_libraries(${PROJECT_NAME}-service_call_repeatedly ${catkin_LIBRARIES})
 
 add_executable(${PROJECT_NAME}-service_exception EXCLUDE_FROM_ALL service_exception.cpp)
 target_link_libraries(${PROJECT_NAME}-service_exception ${GTEST_LIBRARIES} ${catkin_LIBRARIES})
-add_dependencies(${PROJECT_NAME}-service_exception std_srvs_gencpp)
+add_dependencies(${PROJECT_NAME}-service_exception ${std_srvs_EXPORTED_TARGETS})
 
 # Repeatedly call ros::init()
 add_executable(${PROJECT_NAME}-multiple_init_fini EXCLUDE_FROM_ALL multiple_init_fini.cpp)
@@ -147,7 +147,7 @@ target_link_libraries(${PROJECT_NAME}-incrementing_sequence ${GTEST_LIBRARIES} $
 
 add_executable(${PROJECT_NAME}-subscription_callback_types EXCLUDE_FROM_ALL subscription_callback_types.cpp)
 target_link_libraries(${PROJECT_NAME}-subscription_callback_types ${GTEST_LIBRARIES} ${catkin_LIBRARIES})
-add_dependencies(${PROJECT_NAME}-subscription_callback_types std_msgs_gencpp)
+add_dependencies(${PROJECT_NAME}-subscription_callback_types ${std_msgs_EXPORTED_TARGETS})
 
 add_executable(${PROJECT_NAME}-service_callback_types EXCLUDE_FROM_ALL service_callback_types.cpp)
 target_link_libraries(${PROJECT_NAME}-service_callback_types ${GTEST_LIBRARIES} ${catkin_LIBRARIES})
@@ -163,11 +163,11 @@ target_link_libraries(${PROJECT_NAME}-subscribe_retry_tcp ${GTEST_LIBRARIES} ${c
 
 add_executable(${PROJECT_NAME}-subscribe_star EXCLUDE_FROM_ALL subscribe_star.cpp)
 target_link_libraries(${PROJECT_NAME}-subscribe_star ${GTEST_LIBRARIES} ${catkin_LIBRARIES})
-add_dependencies(${PROJECT_NAME}-subscribe_star std_srvs_gencpp)
+add_dependencies(${PROJECT_NAME}-subscribe_star ${std_srvs_EXPORTED_TARGETS})
 
 add_executable(${PROJECT_NAME}-publisher_for_star_subscriber EXCLUDE_FROM_ALL publisher_for_star_subscriber.cpp)
 target_link_libraries(${PROJECT_NAME}-publisher_for_star_subscriber ${catkin_LIBRARIES})
-add_dependencies(${PROJECT_NAME}-publisher_for_star_subscriber std_srvs_gencpp)
+add_dependencies(${PROJECT_NAME}-publisher_for_star_subscriber ${std_srvs_EXPORTED_TARGETS})
 
 add_executable(${PROJECT_NAME}-parameter_validation EXCLUDE_FROM_ALL parameter_validation.cpp)
 target_link_libraries(${PROJECT_NAME}-parameter_validation ${GTEST_LIBRARIES} ${catkin_LIBRARIES})
@@ -192,11 +192,11 @@ target_link_libraries(${PROJECT_NAME}-test_search_param ${GTEST_LIBRARIES} ${cat
 
 add_executable(${PROJECT_NAME}-left_right EXCLUDE_FROM_ALL left_right.cpp)
 target_link_libraries(${PROJECT_NAME}-left_right ${catkin_LIBRARIES})
-add_dependencies(${PROJECT_NAME}-left_right std_msgs_gencpp)
+add_dependencies(${PROJECT_NAME}-left_right ${std_msgs_EXPORTED_TARGETS})
 
 add_executable(${PROJECT_NAME}-string_msg_expect EXCLUDE_FROM_ALL string_msg_expect.cpp)
 target_link_libraries(${PROJECT_NAME}-string_msg_expect ${GTEST_LIBRARIES} ${catkin_LIBRARIES})
-add_dependencies(${PROJECT_NAME}-string_msg_expect std_msgs_gencpp)
+add_dependencies(${PROJECT_NAME}-string_msg_expect ${std_msgs_EXPORTED_TARGETS})
 
 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})
@@ -206,11 +206,11 @@ target_link_libraries(${PROJECT_NAME}-stamped_topic_statistics_empty_timestamp $
 # Call scripts/test_udp_with_dropped_packets.sh to run the test.
 add_executable(${PROJECT_NAME}-publisher EXCLUDE_FROM_ALL publisher.cpp)
 target_link_libraries(${PROJECT_NAME}-publisher ${catkin_LIBRARIES})
-add_dependencies(${PROJECT_NAME}-publisher std_msgs_gencpp)
+add_dependencies(${PROJECT_NAME}-publisher ${std_msgs_EXPORTED_TARGETS})
 
 add_executable(${PROJECT_NAME}-subscriber EXCLUDE_FROM_ALL subscriber.cpp)
 target_link_libraries(${PROJECT_NAME}-subscriber ${catkin_LIBRARIES})
-add_dependencies(${PROJECT_NAME}-subscriber std_msgs_gencpp)
+add_dependencies(${PROJECT_NAME}-subscriber ${std_msgs_EXPORTED_TARGETS})
 
 if(TARGET tests)
   add_dependencies(tests
@@ -279,64 +279,64 @@ if(TARGET tests)
   )
 endif()
 
-add_dependencies(${PROJECT_NAME}-handles ${PROJECT_NAME}_gencpp)
-add_dependencies(${PROJECT_NAME}-timer_callbacks ${PROJECT_NAME}_gencpp)
-add_dependencies(${PROJECT_NAME}-latching_publisher ${PROJECT_NAME}_gencpp)
-add_dependencies(${PROJECT_NAME}-publish_n_fast ${PROJECT_NAME}_gencpp)
-add_dependencies(${PROJECT_NAME}-subscribe_self ${PROJECT_NAME}_gencpp)
-add_dependencies(${PROJECT_NAME}-pub_sub ${PROJECT_NAME}_gencpp)
-add_dependencies(${PROJECT_NAME}-sub_pub ${PROJECT_NAME}_gencpp)
-add_dependencies(${PROJECT_NAME}-publish_empty ${PROJECT_NAME}_gencpp)
-add_dependencies(${PROJECT_NAME}-publish_onsub ${PROJECT_NAME}_gencpp)
-add_dependencies(${PROJECT_NAME}-subscribe_n_fast ${PROJECT_NAME}_gencpp)
-add_dependencies(${PROJECT_NAME}-subscribe_empty ${PROJECT_NAME}_gencpp)
-add_dependencies(${PROJECT_NAME}-subscribe_resubscribe ${PROJECT_NAME}_gencpp)
-add_dependencies(${PROJECT_NAME}-subscribe_unsubscribe ${PROJECT_NAME}_gencpp)
-add_dependencies(${PROJECT_NAME}-publish_unadvertise ${PROJECT_NAME}_gencpp)
-add_dependencies(${PROJECT_NAME}-subscribe_unsubscribe_repeatedly ${PROJECT_NAME}_gencpp)
-add_dependencies(${PROJECT_NAME}-publish_constantly ${PROJECT_NAME}_gencpp)
-add_dependencies(${PROJECT_NAME}-param_update_test ${PROJECT_NAME}_gencpp)
-add_dependencies(${PROJECT_NAME}-real_time_test ${PROJECT_NAME}_gencpp)
-add_dependencies(${PROJECT_NAME}-sim_time_test ${PROJECT_NAME}_gencpp)
-add_dependencies(${PROJECT_NAME}-service_adv ${PROJECT_NAME}_gencpp)
-add_dependencies(${PROJECT_NAME}-service_adv_unadv ${PROJECT_NAME}_gencpp)
-add_dependencies(${PROJECT_NAME}-service_call ${PROJECT_NAME}_gencpp)
-add_dependencies(${PROJECT_NAME}-service_call_zombie ${PROJECT_NAME}_gencpp)
-add_dependencies(${PROJECT_NAME}-service_deadlock ${PROJECT_NAME}_gencpp)
-add_dependencies(${PROJECT_NAME}-service_exception ${PROJECT_NAME}_gencpp)
-add_dependencies(${PROJECT_NAME}-service_call_repeatedly ${PROJECT_NAME}_gencpp)
-add_dependencies(${PROJECT_NAME}-multiple_init_fini ${PROJECT_NAME}_gencpp)
-add_dependencies(${PROJECT_NAME}-inspection ${PROJECT_NAME}_gencpp)
-add_dependencies(${PROJECT_NAME}-service_adv_multiple ${PROJECT_NAME}_gencpp)
-add_dependencies(${PROJECT_NAME}-service_adv_a ${PROJECT_NAME}_gencpp)
-add_dependencies(${PROJECT_NAME}-service_wait_a_adv_b ${PROJECT_NAME}_gencpp)
-add_dependencies(${PROJECT_NAME}-service_call_expect_b ${PROJECT_NAME}_gencpp)
-add_dependencies(${PROJECT_NAME}-service_adv_zombie ${PROJECT_NAME}_gencpp)
-add_dependencies(${PROJECT_NAME}-name_remapping ${PROJECT_NAME}_gencpp)
-add_dependencies(${PROJECT_NAME}-name_remapping_with_ns ${PROJECT_NAME}_gencpp)
-add_dependencies(${PROJECT_NAME}-namespaces ${PROJECT_NAME}_gencpp)
-add_dependencies(${PROJECT_NAME}-params ${PROJECT_NAME}_gencpp)
-add_dependencies(${PROJECT_NAME}-get_master_information ${PROJECT_NAME}_gencpp)
-add_dependencies(${PROJECT_NAME}-multiple_subscriptions ${PROJECT_NAME}_gencpp)
-add_dependencies(${PROJECT_NAME}-check_master ${PROJECT_NAME}_gencpp)
-add_dependencies(${PROJECT_NAME}-wait_for_message ${PROJECT_NAME}_gencpp)
-add_dependencies(${PROJECT_NAME}-loads_of_publishers ${PROJECT_NAME}_gencpp)
-add_dependencies(${PROJECT_NAME}-incrementing_sequence ${PROJECT_NAME}_gencpp)
-add_dependencies(${PROJECT_NAME}-subscription_callback_types ${PROJECT_NAME}_gencpp)
-add_dependencies(${PROJECT_NAME}-service_callback_types ${PROJECT_NAME}_gencpp)
-add_dependencies(${PROJECT_NAME}-intraprocess_subscriptions ${PROJECT_NAME}_gencpp)
-add_dependencies(${PROJECT_NAME}-nonconst_subscriptions ${PROJECT_NAME}_gencpp)
-add_dependencies(${PROJECT_NAME}-subscribe_retry_tcp ${PROJECT_NAME}_gencpp)
-add_dependencies(${PROJECT_NAME}-subscribe_star ${PROJECT_NAME}_gencpp)
-add_dependencies(${PROJECT_NAME}-publisher_for_star_subscriber ${PROJECT_NAME}_gencpp)
-add_dependencies(${PROJECT_NAME}-parameter_validation ${PROJECT_NAME}_gencpp)
-add_dependencies(${PROJECT_NAME}-param_locale_avoidance_test ${PROJECT_NAME}_gencpp)
-add_dependencies(${PROJECT_NAME}-crashes_under_gprof ${PROJECT_NAME}_gencpp)
-add_dependencies(${PROJECT_NAME}-test_remapping ${PROJECT_NAME}_gencpp)
-add_dependencies(${PROJECT_NAME}-name_not_remappable ${PROJECT_NAME}_gencpp)
-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}-handles ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-timer_callbacks ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-latching_publisher ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-publish_n_fast ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-subscribe_self ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-pub_sub ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-sub_pub ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-publish_empty ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-publish_onsub ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-subscribe_n_fast ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-subscribe_empty ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-subscribe_resubscribe ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-subscribe_unsubscribe ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-publish_unadvertise ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-subscribe_unsubscribe_repeatedly ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-publish_constantly ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-param_update_test ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-real_time_test ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-sim_time_test ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-service_adv ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-service_adv_unadv ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-service_call ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-service_call_zombie ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-service_deadlock ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-service_exception ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-service_call_repeatedly ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-multiple_init_fini ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-inspection ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-service_adv_multiple ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-service_adv_a ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-service_wait_a_adv_b ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-service_call_expect_b ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-service_adv_zombie ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-name_remapping ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-name_remapping_with_ns ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-namespaces ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-params ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-get_master_information ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-multiple_subscriptions ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-check_master ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-wait_for_message ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-loads_of_publishers ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-incrementing_sequence ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-subscription_callback_types ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-service_callback_types ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-intraprocess_subscriptions ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-nonconst_subscriptions ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-subscribe_retry_tcp ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-subscribe_star ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-publisher_for_star_subscriber ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-parameter_validation ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-param_locale_avoidance_test ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-crashes_under_gprof ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-test_remapping ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-name_not_remappable ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-test_ns_node_remapping ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-test_search_param ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-left_right ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}-string_msg_expect ${${PROJECT_NAME}_EXPORTED_TARGETS})
 add_dependencies(${PROJECT_NAME}-stamped_topic_statistics_empty_timestamp
- ${PROJECT_NAME}_gencpp)
+ ${${PROJECT_NAME}_EXPORTED_TARGETS})
diff --git a/test/test_roscpp/test/src/handles.cpp b/test/test_roscpp/test/src/handles.cpp
index aa039f3..968150e 100644
--- a/test/test_roscpp/test/src/handles.cpp
+++ b/test/test_roscpp/test/src/handles.cpp
@@ -122,7 +122,7 @@ TEST(RoscppHandles, nodeHandleParentWithRemappings)
 }
 
 int32_t g_recv_count = 0;
-void subscriberCallback(const test_roscpp::TestArray::ConstPtr& msg)
+void subscriberCallback(const test_roscpp::TestArray::ConstPtr&)
 {
   ++g_recv_count;
 }
@@ -134,7 +134,7 @@ public:
   : recv_count_(0)
   {}
 
-  void callback(const test_roscpp::TestArray::ConstPtr& msg)
+  void callback(const test_roscpp::TestArray::ConstPtr&)
   {
     ++recv_count_;
   }
@@ -350,7 +350,7 @@ TEST(RoscppHandles, publisherMultiple)
   ASSERT_TRUE(std::find(topics.begin(), topics.end(), "/test") == topics.end());
 }
 
-bool serviceCallback(TestStringString::Request& req, TestStringString::Response& res)
+bool serviceCallback(TestStringString::Request&, TestStringString::Response&)
 {
   return true;
 }
@@ -433,7 +433,7 @@ TEST(RoscppHandles, serviceAdvMultiple)
 }
 
 int32_t g_sub_count = 0;
-void connectedCallback(const ros::SingleSubscriberPublisher& pub)
+void connectedCallback(const ros::SingleSubscriberPublisher&)
 {
   ++g_sub_count;
 }
@@ -442,7 +442,7 @@ TEST(RoscppHandles, trackedObjectWithAdvertiseSubscriberCallback)
 {
   ros::NodeHandle n;
 
-  boost::shared_ptr<char> tracked(new char);
+  boost::shared_ptr<char> tracked(boost::make_shared<char>());
 
   ros::Publisher pub = n.advertise<test_roscpp::TestArray>("/test", 0, connectedCallback, SubscriberStatusCallback(), tracked);
 
@@ -519,7 +519,7 @@ TEST(RoscppHandles, multiplePublishersWithSubscriberConnectCallback)
 class ServiceClass
 {
 public:
-  bool serviceCallback(TestStringString::Request& req, TestStringString::Response& res)
+  bool serviceCallback(TestStringString::Request&, TestStringString::Response&)
   {
     return true;
   }
@@ -533,7 +533,7 @@ TEST(RoscppHandles, trackedObjectWithServiceCallback)
   n.setCallbackQueue(&queue);
   boost::thread th(boost::bind(pump, &queue));
 
-  boost::shared_ptr<ServiceClass> tracked(new ServiceClass);
+  boost::shared_ptr<ServiceClass> tracked(boost::make_shared<ServiceClass>());
   ros::ServiceServer srv = n.advertiseService("/test_srv", &ServiceClass::serviceCallback, tracked);
 
   TestStringString t;
@@ -551,7 +551,7 @@ TEST(RoscppHandles, trackedObjectWithSubscriptionCallback)
 {
   ros::NodeHandle n;
 
-  boost::shared_ptr<SubscribeHelper> tracked(new SubscribeHelper);
+  boost::shared_ptr<SubscribeHelper> tracked(boost::make_shared<SubscribeHelper>());
 
   g_recv_count = 0;
   ros::Subscriber sub = n.subscribe("/test", 0, &SubscribeHelper::callback, tracked);
diff --git a/test/test_roscpp/test/src/intraprocess_subscriptions.cpp b/test/test_roscpp/test/src/intraprocess_subscriptions.cpp
index dbd02a3..be36ab9 100644
--- a/test/test_roscpp/test/src/intraprocess_subscriptions.cpp
+++ b/test/test_roscpp/test/src/intraprocess_subscriptions.cpp
@@ -90,18 +90,18 @@ template<>
 struct Serializer<Msg>
 {
   template<typename Stream>
-  inline static void write(Stream& stream, const Msg& v)
+  inline static void write(Stream&, const Msg& v)
   {
     v.serialized = true;
   }
 
   template<typename Stream>
-  inline static void read(Stream& stream, Msg& v)
+  inline static void read(Stream&, Msg& v)
   {
     v.deserialized = true;
   }
 
-  inline static uint32_t serializedLength(const Msg& v)
+  inline static uint32_t serializedLength(const Msg&)
   {
     return 0;
   }
@@ -157,18 +157,18 @@ template<>
 struct Serializer<Msg2>
 {
   template<typename Stream>
-  inline static void write(Stream& stream, const Msg2& v)
+  inline static void write(Stream&, const Msg2& v)
   {
     v.serialized = true;
   }
 
   template<typename Stream>
-  inline static void read(Stream& stream, Msg2& v)
+  inline static void read(Stream&, Msg2& v)
   {
     v.deserialized = true;
   }
 
-  inline static uint32_t serializedLength(const Msg2& v)
+  inline static uint32_t serializedLength(const Msg2&)
   {
     return 0;
   }
@@ -190,7 +190,7 @@ TEST(IntraprocessSubscriptions, noCopy)
   ros::Subscriber sub = nh.subscribe("test", 0, messageCallback);
   ros::Publisher pub = nh.advertise<Msg>("test", 0);
 
-  MsgConstPtr msg(new Msg);
+  MsgConstPtr msg(boost::make_shared<Msg>());
 
   while (pub.getNumSubscribers() == 0)
   {
@@ -221,7 +221,7 @@ TEST(IntraprocessSubscriptions, differentRTTI)
   ros::Subscriber sub = nh.subscribe("test", 0, messageCallback);
   ros::Publisher pub = nh.advertise<Msg2>("test", 0);
 
-  Msg2ConstPtr msg(new Msg2);
+  Msg2ConstPtr msg(boost::make_shared<Msg2>());
 
   while (pub.getNumSubscribers() == 0)
   {
@@ -259,7 +259,7 @@ TEST(IntraprocessSubscriptions, noCopyAndDifferentRTTI)
   ros::Subscriber sub2 = nh.subscribe("test", 0, messageCallback2);
   ros::Publisher pub = nh.advertise<Msg2>("test", 0);
 
-  Msg2ConstPtr msg(new Msg2);
+  Msg2ConstPtr msg(boost::make_shared<Msg2>());
 
   while (pub.getNumSubscribers() == 0)
   {
diff --git a/test/test_roscpp/test/src/loads_of_publishers.cpp b/test/test_roscpp/test/src/loads_of_publishers.cpp
index 8e9c4b4..aae6ad6 100644
--- a/test/test_roscpp/test/src/loads_of_publishers.cpp
+++ b/test/test_roscpp/test/src/loads_of_publishers.cpp
@@ -37,9 +37,8 @@
 
 uint32_t g_pub_count = 0;
 
-void callback(const test_roscpp::TestArrayConstPtr& msg)
+void callback(const test_roscpp::TestArrayConstPtr&)
 {
-
 }
 
 TEST(LoadsOfPublishers, waitForAll)
diff --git a/test/test_roscpp/test/src/multiple_init_fini.cpp b/test/test_roscpp/test/src/multiple_init_fini.cpp
index 8f818f3..c8afa26 100644
--- a/test/test_roscpp/test/src/multiple_init_fini.cpp
+++ b/test/test_roscpp/test/src/multiple_init_fini.cpp
@@ -46,7 +46,7 @@
 int g_argc;
 char** g_argv;
 
-void callback(const test_roscpp::TestArrayConstPtr& msg)
+void callback(const test_roscpp::TestArrayConstPtr&)
 {
 }
 
diff --git a/test/test_roscpp/test/src/nonconst_subscriptions.cpp b/test/test_roscpp/test/src/nonconst_subscriptions.cpp
index 0118f10..b9e368c 100644
--- a/test/test_roscpp/test/src/nonconst_subscriptions.cpp
+++ b/test/test_roscpp/test/src/nonconst_subscriptions.cpp
@@ -71,7 +71,7 @@ TEST(NonConstSubscriptions, oneNonConstSubscriber)
   ros::Subscriber sub = nh.subscribe("test", 0, &NonConstHelper::callback, &h);
   ros::Publisher pub = nh.advertise<test_roscpp::TestEmpty>("test", 0);
 
-  test_roscpp::TestEmptyPtr msg(new test_roscpp::TestEmpty);
+  test_roscpp::TestEmptyPtr msg(boost::make_shared<test_roscpp::TestEmpty>());
   pub.publish(msg);
   ros::spinOnce();
 
@@ -88,7 +88,7 @@ TEST(NonConstSubscriptions, oneConstOneNonConst)
   ros::Subscriber sub2 = nh.subscribe("test", 0, &ConstHelper::callback, &h2);
   ros::Publisher pub = nh.advertise<test_roscpp::TestEmpty>("test", 0);
 
-  test_roscpp::TestEmptyPtr msg(new test_roscpp::TestEmpty);
+  test_roscpp::TestEmptyPtr msg(boost::make_shared<test_roscpp::TestEmpty>());
   pub.publish(msg);
   ros::spinOnce();
 
@@ -106,7 +106,7 @@ TEST(NonConstSubscriptions, twoNonConst)
   ros::Subscriber sub2 = nh.subscribe("test", 0, &NonConstHelper::callback, &h2);
   ros::Publisher pub = nh.advertise<test_roscpp::TestEmpty>("test", 0);
 
-  test_roscpp::TestEmptyPtr msg(new test_roscpp::TestEmpty);
+  test_roscpp::TestEmptyPtr msg(boost::make_shared<test_roscpp::TestEmpty>());
   pub.publish(msg);
   ros::spinOnce();
 
@@ -123,7 +123,7 @@ TEST(NonConstSubscriptions, twoConst)
   ros::Subscriber sub2 = nh.subscribe("test", 0, &ConstHelper::callback, &h2);
   ros::Publisher pub = nh.advertise<test_roscpp::TestEmpty>("test", 0);
 
-  test_roscpp::TestEmptyPtr msg(new test_roscpp::TestEmpty);
+  test_roscpp::TestEmptyPtr msg(boost::make_shared<test_roscpp::TestEmpty>());
   pub.publish(msg);
   ros::spinOnce();
 
diff --git a/test/test_roscpp/test/src/params.cpp b/test/test_roscpp/test/src/params.cpp
index 39df6ba..a54888b 100644
--- a/test/test_roscpp/test/src/params.cpp
+++ b/test/test_roscpp/test/src/params.cpp
@@ -560,6 +560,12 @@ TEST(Params, paramNodeHandleTemplateFunction)
   EXPECT_EQ( nh.param<bool>( "loob", true ), true );
 }
 
+TEST(Params, getParamNames) {
+  std::vector<std::string> test_params;
+  EXPECT_TRUE(ros::param::getParamNames(test_params));
+  EXPECT_LT(10, test_params.size());
+}
+
 int
 main(int argc, char** argv)
 {
diff --git a/test/test_roscpp/test/src/service_adv_a.cpp b/test/test_roscpp/test/src/service_adv_a.cpp
index 9d8ead5..1cf6fcc 100644
--- a/test/test_roscpp/test/src/service_adv_a.cpp
+++ b/test/test_roscpp/test/src/service_adv_a.cpp
@@ -43,7 +43,7 @@
 #include <sys/wait.h>
 #include <cstdlib>
 
-bool srvCallback(test_roscpp::TestStringString::Request  &req,
+bool srvCallback(test_roscpp::TestStringString::Request &,
                  test_roscpp::TestStringString::Response &res)
 {
   res.str = "A";
diff --git a/test/test_roscpp/test/src/service_adv_multiple.cpp b/test/test_roscpp/test/src/service_adv_multiple.cpp
index 22eb16c..89ac6a8 100644
--- a/test/test_roscpp/test/src/service_adv_multiple.cpp
+++ b/test/test_roscpp/test/src/service_adv_multiple.cpp
@@ -41,8 +41,8 @@
 #include "ros/service.h"
 #include <test_roscpp/TestStringString.h>
 
-bool srvCallback(test_roscpp::TestStringString::Request  &req,
-                 test_roscpp::TestStringString::Response &res)
+bool srvCallback(test_roscpp::TestStringString::Request &,
+                 test_roscpp::TestStringString::Response &)
 {
   return true;
 }
diff --git a/test/test_roscpp/test/src/service_adv_unadv.cpp b/test/test_roscpp/test/src/service_adv_unadv.cpp
index 86e4a23..f445399 100644
--- a/test/test_roscpp/test/src/service_adv_unadv.cpp
+++ b/test/test_roscpp/test/src/service_adv_unadv.cpp
@@ -51,8 +51,8 @@ class ServiceAdvertiser : public testing::Test
     bool advertised_;
     bool failure_;
 
-    bool srvCallback(test_roscpp::TestStringString::Request  &req,
-                     test_roscpp::TestStringString::Response &res)
+    bool srvCallback(test_roscpp::TestStringString::Request &,
+                     test_roscpp::TestStringString::Response &)
     {
       ROS_INFO("in callback");
       if(!advertised_)
diff --git a/test/test_roscpp/test/src/service_adv_zombie.cpp b/test/test_roscpp/test/src/service_adv_zombie.cpp
index 6393a27..e5508c5 100644
--- a/test/test_roscpp/test/src/service_adv_zombie.cpp
+++ b/test/test_roscpp/test/src/service_adv_zombie.cpp
@@ -35,7 +35,7 @@
 
 #include <stdlib.h>
 
-bool srvCallback(test_roscpp::TestStringString::Request  &req,
+bool srvCallback(test_roscpp::TestStringString::Request &,
                  test_roscpp::TestStringString::Response &res)
 {
   res.str = "B";
diff --git a/test/test_roscpp/test/src/service_callback_types.cpp b/test/test_roscpp/test/src/service_callback_types.cpp
index f2f8949..aed4a4a 100644
--- a/test/test_roscpp/test/src/service_callback_types.cpp
+++ b/test/test_roscpp/test/src/service_callback_types.cpp
@@ -40,36 +40,36 @@
 
 #include <vector>
 
-bool add(test_roscpp::TestStringString::Request  &req,
-         test_roscpp::TestStringString::Response &res )
+bool add(test_roscpp::TestStringString::Request &,
+         test_roscpp::TestStringString::Response &)
 {
   return true;
 }
 
-bool add2(ros::ServiceEvent<test_roscpp::TestStringString::Request, test_roscpp::TestStringString::Response>& event)
+bool add2(ros::ServiceEvent<test_roscpp::TestStringString::Request, test_roscpp::TestStringString::Response>&)
 {
   return true;
 }
 
-bool add3(ros::ServiceEvent<test_roscpp::TestStringString::Request, test_roscpp::TestStringString::Response>& event, const std::string& bound)
+bool add3(ros::ServiceEvent<test_roscpp::TestStringString::Request, test_roscpp::TestStringString::Response>&, const std::string&)
 {
   return true;
 }
 
 struct A
 {
-  bool add(test_roscpp::TestStringString::Request  &req,
-           test_roscpp::TestStringString::Response &res )
+  bool add(test_roscpp::TestStringString::Request &,
+           test_roscpp::TestStringString::Response &)
   {
     return true;
   }
 
-  bool add2(ros::ServiceEvent<test_roscpp::TestStringString::Request, test_roscpp::TestStringString::Response>& event)
+  bool add2(ros::ServiceEvent<test_roscpp::TestStringString::Request, test_roscpp::TestStringString::Response>&)
   {
     return true;
   }
 
-  bool add3(ros::ServiceEvent<test_roscpp::TestStringString::Request, test_roscpp::TestStringString::Response>& event, const std::string& bound)
+  bool add3(ros::ServiceEvent<test_roscpp::TestStringString::Request, test_roscpp::TestStringString::Response>&, const std::string&)
   {
     return true;
   }
diff --git a/test/test_roscpp/test/src/service_deadlock.cpp b/test/test_roscpp/test/src/service_deadlock.cpp
index b7b0371..d2cfccc 100644
--- a/test/test_roscpp/test/src/service_deadlock.cpp
+++ b/test/test_roscpp/test/src/service_deadlock.cpp
@@ -6,7 +6,7 @@
 #include <ros/console.h>
 #include <ros/poll_manager.h>
 
-bool dummyService(std_srvs::Empty::Request &req,std_srvs::Empty::Request &res)
+bool dummyService(std_srvs::Empty::Request &, std_srvs::Empty::Request &)
 {
   return true;
 }
diff --git a/test/test_roscpp/test/src/service_exception.cpp b/test/test_roscpp/test/src/service_exception.cpp
index 845fd60..05d166e 100644
--- a/test/test_roscpp/test/src/service_exception.cpp
+++ b/test/test_roscpp/test/src/service_exception.cpp
@@ -43,7 +43,7 @@ typedef log4cxx::helpers::ObjectPtrT<ListAppender> ListAppenderPtr;
 
 static const char EXCEPTION[] = "custom exception message";
 
-bool throwingService(std_srvs::Empty::Request& req, std_srvs::Empty::Request& res)
+bool throwingService(std_srvs::Empty::Request&, std_srvs::Empty::Request&)
 {
   throw std::runtime_error(EXCEPTION);
   return true;
diff --git a/test/test_roscpp/test/src/service_wait_a_adv_b.cpp b/test/test_roscpp/test/src/service_wait_a_adv_b.cpp
index 09220a5..37bd5aa 100644
--- a/test/test_roscpp/test/src/service_wait_a_adv_b.cpp
+++ b/test/test_roscpp/test/src/service_wait_a_adv_b.cpp
@@ -36,7 +36,7 @@
 #include "ros/ros.h"
 #include <test_roscpp/TestStringString.h>
 
-bool srvCallback(test_roscpp::TestStringString::Request  &req,
+bool srvCallback(test_roscpp::TestStringString::Request &,
                  test_roscpp::TestStringString::Response &res)
 {
   res.str = "B";
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
index a8bf089..08f1a49 100644
--- a/test/test_roscpp/test/src/stamped_topic_statistics_empty_timestamp.cpp
+++ b/test/test_roscpp/test/src/stamped_topic_statistics_empty_timestamp.cpp
@@ -33,7 +33,7 @@
 
 #include <test_roscpp/TestWithHeader.h>
 
-void callback(const test_roscpp::TestWithHeaderConstPtr& msg)
+void callback(const test_roscpp::TestWithHeaderConstPtr&)
 {
   // No operation needed here
 }
diff --git a/test/test_roscpp/test/src/subscribe_empty.cpp b/test/test_roscpp/test/src/subscribe_empty.cpp
index 553a249..f096655 100644
--- a/test/test_roscpp/test/src/subscribe_empty.cpp
+++ b/test/test_roscpp/test/src/subscribe_empty.cpp
@@ -56,7 +56,7 @@ class Subscriptions : public testing::Test
     int msg_i;
     ros::Duration dt;
 
-    void messageCallback(const test_roscpp::TestEmptyConstPtr& msg)
+    void messageCallback(const test_roscpp::TestEmptyConstPtr&)
     {
       if(failure || success)
         return;
diff --git a/test/test_roscpp/test/src/subscribe_retry_tcp.cpp b/test/test_roscpp/test/src/subscribe_retry_tcp.cpp
index 7270539..5dd0a07 100644
--- a/test/test_roscpp/test/src/subscribe_retry_tcp.cpp
+++ b/test/test_roscpp/test/src/subscribe_retry_tcp.cpp
@@ -40,7 +40,7 @@
 #include "roscpp/Empty.h"
 
 int32_t g_count = 0;
-void callback(const test_roscpp::TestArrayConstPtr& msg)
+void callback(const test_roscpp::TestArrayConstPtr&)
 {
   ++g_count;
 }
diff --git a/test/test_roscpp/test/src/subscribe_star.cpp b/test/test_roscpp/test/src/subscribe_star.cpp
index bb430d5..7e6f70e 100644
--- a/test/test_roscpp/test/src/subscribe_star.cpp
+++ b/test/test_roscpp/test/src/subscribe_star.cpp
@@ -79,7 +79,7 @@ template<>
 struct Serializer<AnyMessage>
 {
   template<typename Stream, typename T>
-  static void allInOne(Stream s, T t)
+  static void allInOne(Stream, T)
   {
   }
 
@@ -95,7 +95,7 @@ struct AnyHelper
   {
   }
 
-  void cb(const AnyMessageConstPtr& msg)
+  void cb(const AnyMessageConstPtr&)
   {
     ++count;
   }
@@ -114,7 +114,7 @@ TEST(SubscribeStar, simpleSubFirstIntra)
   EXPECT_EQ(pub.getNumSubscribers(), 1U);
   EXPECT_EQ(sub.getNumPublishers(), 1U);
 
-  AnyMessagePtr msg(new AnyMessage);
+  AnyMessagePtr msg(boost::make_shared<AnyMessage>());
   pub.publish(msg);
   ros::spinOnce();
   EXPECT_EQ(h.count, 1U);
@@ -130,7 +130,7 @@ TEST(SubscribeStar, simplePubFirstIntra)
   EXPECT_EQ(pub.getNumSubscribers(), 1U);
   EXPECT_EQ(sub.getNumPublishers(), 1U);
 
-  AnyMessagePtr msg(new AnyMessage);
+  AnyMessagePtr msg(boost::make_shared<AnyMessage>());
   pub.publish(msg);
   ros::spinOnce();
   EXPECT_EQ(h.count, 1U);
diff --git a/test/test_roscpp/test/src/subscribe_unsubscribe.cpp b/test/test_roscpp/test/src/subscribe_unsubscribe.cpp
index faaf052..d3fa5d4 100644
--- a/test/test_roscpp/test/src/subscribe_unsubscribe.cpp
+++ b/test/test_roscpp/test/src/subscribe_unsubscribe.cpp
@@ -54,7 +54,7 @@ public:
   ros::NodeHandle nh_;
   ros::Subscriber sub_;
 
-  void messageCallback(const test_roscpp::TestArrayConstPtr& msg)
+  void messageCallback(const test_roscpp::TestArrayConstPtr&)
   {
     ROS_INFO("in callback");
 
@@ -65,7 +65,7 @@ public:
     }
   }
 
-  void autoUnsubscribeCallback(const test_roscpp::TestArrayConstPtr& msg)
+  void autoUnsubscribeCallback(const test_roscpp::TestArrayConstPtr&)
   {
     ROS_INFO("in autounsub callback");
     sub_.shutdown();
diff --git a/test/test_roscpp/test/src/subscribe_unsubscribe_repeatedly.cpp b/test/test_roscpp/test/src/subscribe_unsubscribe_repeatedly.cpp
index 0ec218f..f88fcb6 100644
--- a/test/test_roscpp/test/src/subscribe_unsubscribe_repeatedly.cpp
+++ b/test/test_roscpp/test/src/subscribe_unsubscribe_repeatedly.cpp
@@ -32,7 +32,7 @@
 #include "ros/ros.h"
 #include <test_roscpp/TestArray.h>
 
-void callback(const test_roscpp::TestArrayConstPtr& msg)
+void callback(const test_roscpp::TestArrayConstPtr&)
 {
 }
 
diff --git a/test/test_roscpp/test/src/timer_callbacks.cpp b/test/test_roscpp/test/src/timer_callbacks.cpp
index 6204339..b016ee5 100644
--- a/test/test_roscpp/test/src/timer_callbacks.cpp
+++ b/test/test_roscpp/test/src/timer_callbacks.cpp
@@ -333,7 +333,7 @@ TEST(RoscppTimerCallbacks, stopWallTimer)
 }
 
 int32_t g_count = 0;
-void timerCallback(const ros::WallTimerEvent& evt)
+void timerCallback(const ros::WallTimerEvent&)
 {
   ++g_count;
 }
@@ -387,7 +387,7 @@ public:
     timer_ = n.createTimer(r, &TimerHelper::callback, this, oneshot);
   }
 
-  void callback(const TimerEvent& e)
+  void callback(const TimerEvent&)
   {
     ++total_calls_;
   }
@@ -594,7 +594,7 @@ public:
     g_count = 0;
   }
 
-  void callback(const TimerEvent& e)
+  void callback(const TimerEvent&)
   {
     ++g_count;
   }
@@ -606,7 +606,7 @@ TEST(RoscppTimerCallbacks, trackedObject)
   Time now(1, 0);
   Time::setNow(now);
 
-  boost::shared_ptr<Tracked> tracked(new Tracked);
+  boost::shared_ptr<Tracked> tracked(boost::make_shared<Tracked>());
   Timer timer = n.createTimer(Duration(0.001), &Tracked::callback, tracked);
 
   now += Duration(0.1);
diff --git a/test/test_roscpp/test/test_callback_queue.cpp b/test/test_roscpp/test/test_callback_queue.cpp
index de08900..a9cba89 100644
--- a/test/test_roscpp/test/test_callback_queue.cpp
+++ b/test/test_roscpp/test/test_callback_queue.cpp
@@ -67,7 +67,7 @@ typedef boost::shared_ptr<CountingCallback> CountingCallbackPtr;
 
 TEST(CallbackQueue, singleCallback)
 {
-  CountingCallbackPtr cb(new CountingCallback);
+  CountingCallbackPtr cb(boost::make_shared<CountingCallback>());
   CallbackQueue queue;
   queue.addCallback(cb, 1);
   queue.callOne();
@@ -88,7 +88,7 @@ TEST(CallbackQueue, singleCallback)
 
 TEST(CallbackQueue, multipleCallbacksCallAvailable)
 {
-  CountingCallbackPtr cb(new CountingCallback);
+  CountingCallbackPtr cb(boost::make_shared<CountingCallback>());
   CallbackQueue queue;
   for (uint32_t i = 0; i < 1000; ++i)
   {
@@ -102,7 +102,7 @@ TEST(CallbackQueue, multipleCallbacksCallAvailable)
 
 TEST(CallbackQueue, multipleCallbacksCallOne)
 {
-  CountingCallbackPtr cb(new CountingCallback);
+  CountingCallbackPtr cb(boost::make_shared<CountingCallback>());
   CallbackQueue queue;
   for (uint32_t i = 0; i < 1000; ++i)
   {
@@ -118,8 +118,8 @@ TEST(CallbackQueue, multipleCallbacksCallOne)
 
 TEST(CallbackQueue, remove)
 {
-  CountingCallbackPtr cb1(new CountingCallback);
-  CountingCallbackPtr cb2(new CountingCallback);
+  CountingCallbackPtr cb1(boost::make_shared<CountingCallback>());
+  CountingCallbackPtr cb2(boost::make_shared<CountingCallback>());
   CallbackQueue queue;
   queue.addCallback(cb1, 1);
   queue.addCallback(cb2, 2);
@@ -158,8 +158,8 @@ typedef boost::shared_ptr<SelfRemovingCallback> SelfRemovingCallbackPtr;
 TEST(CallbackQueue, removeSelf)
 {
   CallbackQueue queue;
-  SelfRemovingCallbackPtr cb1(new SelfRemovingCallback(&queue, 1));
-  CountingCallbackPtr cb2(new CountingCallback());
+  SelfRemovingCallbackPtr cb1(boost::make_shared<SelfRemovingCallback>(&queue, 1));
+  CountingCallbackPtr cb2(boost::make_shared<CountingCallback>());
   queue.addCallback(cb1, 1);
   queue.addCallback(cb2, 1);
   queue.addCallback(cb2, 1);
@@ -212,7 +212,7 @@ typedef boost::shared_ptr<RecursiveCallback> RecursiveCallbackPtr;
 TEST(CallbackQueue, recursive1)
 {
   CallbackQueue queue;
-  RecursiveCallbackPtr cb(new RecursiveCallback(&queue, true));
+  RecursiveCallbackPtr cb(boost::make_shared<RecursiveCallback>(&queue, true));
   queue.addCallback(cb, 1);
   queue.addCallback(cb, 1);
   queue.addCallback(cb, 1);
@@ -224,7 +224,7 @@ TEST(CallbackQueue, recursive1)
 TEST(CallbackQueue, recursive2)
 {
   CallbackQueue queue;
-  RecursiveCallbackPtr cb(new RecursiveCallback(&queue, false));
+  RecursiveCallbackPtr cb(boost::make_shared<RecursiveCallback>(&queue, false));
   queue.addCallback(cb, 1);
   queue.addCallback(cb, 1);
   queue.addCallback(cb, 1);
@@ -236,7 +236,7 @@ TEST(CallbackQueue, recursive2)
 TEST(CallbackQueue, recursive3)
 {
   CallbackQueue queue;
-  RecursiveCallbackPtr cb(new RecursiveCallback(&queue, false));
+  RecursiveCallbackPtr cb(boost::make_shared<RecursiveCallback>(&queue, false));
   queue.addCallback(cb, 1);
   queue.addCallback(cb, 1);
   queue.addCallback(cb, 1);
@@ -248,7 +248,7 @@ TEST(CallbackQueue, recursive3)
 TEST(CallbackQueue, recursive4)
 {
   CallbackQueue queue;
-  RecursiveCallbackPtr cb(new RecursiveCallback(&queue, true));
+  RecursiveCallbackPtr cb(boost::make_shared<RecursiveCallback>(&queue, true));
   queue.addCallback(cb, 1);
   queue.addCallback(cb, 1);
   queue.addCallback(cb, 1);
@@ -297,7 +297,7 @@ size_t runThreadedTest(const CountingCallbackPtr& cb, const boost::function<void
 
 TEST(CallbackQueue, threadedCallAvailable)
 {
-  CountingCallbackPtr cb(new CountingCallback);
+  CountingCallbackPtr cb(boost::make_shared<CountingCallback>());
   size_t i = runThreadedTest(cb, callAvailableThread);
   ROS_INFO_STREAM(i);
   EXPECT_EQ(cb->count, i);
@@ -313,7 +313,7 @@ void callOneThread(CallbackQueue* queue, bool& done)
 
 TEST(CallbackQueue, threadedCallOne)
 {
-  CountingCallbackPtr cb(new CountingCallback);
+  CountingCallbackPtr cb(boost::make_shared<CountingCallback>());
   size_t i = runThreadedTest(cb, callOneThread);
   ROS_INFO_STREAM(i);
   EXPECT_EQ(cb->count, i);
@@ -378,7 +378,7 @@ TEST(CallbackQueue, recursiveTimer)
   ros::Time::init();
   CallbackQueue queue;
   recursiveTimerQueue = &queue;
-  TimerRecursionCallbackPtr cb(new TimerRecursionCallback(&queue));
+  TimerRecursionCallbackPtr cb(boost::make_shared<TimerRecursionCallback>(&queue));
   queue.addCallback(cb, 1);
 
   boost::thread_group tg;
diff --git a/test/test_roscpp/test/test_spinners.cpp b/test/test_roscpp/test/test_spinners.cpp
index 841ffbc..8645399 100644
--- a/test/test_roscpp/test/test_spinners.cpp
+++ b/test/test_roscpp/test/test_spinners.cpp
@@ -53,7 +53,7 @@ using namespace ros;
 int argc_;
 char** argv_;
 
-void fire_shutdown(const ros::WallTimerEvent& event) {
+void fire_shutdown(const ros::WallTimerEvent&) {
   ROS_INFO("Asking for shutdown");
   ros::shutdown();
 }
diff --git a/test/test_roscpp/test/test_subscription_queue.cpp b/test/test_roscpp/test/test_subscription_queue.cpp
index 0408a77..9af94a2 100644
--- a/test/test_roscpp/test/test_subscription_queue.cpp
+++ b/test/test_roscpp/test/test_subscription_queue.cpp
@@ -53,7 +53,7 @@ public:
   virtual const std::string __getMD5Sum() const { return ""; }
   virtual const std::string __getMessageDefinition() const { return ""; }
   virtual uint32_t serializationLength() const { return 0; }
-  virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const { return write_ptr; }
+  virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const { (void)seq; return write_ptr; }
   virtual uint8_t *deserialize(uint8_t *read_ptr) { return read_ptr; }
 };
 
@@ -66,7 +66,7 @@ public:
 
   virtual VoidConstPtr deserialize(const SubscriptionCallbackHelperDeserializeParams&)
   {
-    return VoidConstPtr(new FakeMessage);
+    return boost::make_shared<FakeMessage>();
   }
 
   virtual std::string getMD5Sum() { return ""; }
@@ -74,6 +74,7 @@ public:
 
   virtual void call(SubscriptionCallbackHelperCallParams& params)
   {
+    (void)params;
     {
       boost::mutex::scoped_lock lock(mutex_);
       ++calls_;
@@ -100,8 +101,8 @@ TEST(SubscriptionQueue, queueSize)
 {
   SubscriptionQueue queue("blah", 1, false);
 
-  FakeSubHelperPtr helper(new FakeSubHelper);
-  MessageDeserializerPtr des(new MessageDeserializer(helper, SerializedMessage(), boost::shared_ptr<M_string>()));
+  FakeSubHelperPtr helper(boost::make_shared<FakeSubHelper>());
+  MessageDeserializerPtr des(boost::make_shared<MessageDeserializer>(helper, SerializedMessage(), boost::shared_ptr<M_string>()));
 
   ASSERT_FALSE(queue.full());
 
@@ -133,8 +134,8 @@ TEST(SubscriptionQueue, infiniteQueue)
 {
   SubscriptionQueue queue("blah", 0, false);
 
-  FakeSubHelperPtr helper(new FakeSubHelper);
-  MessageDeserializerPtr des(new MessageDeserializer(helper, SerializedMessage(), boost::shared_ptr<M_string>()));
+  FakeSubHelperPtr helper(boost::make_shared<FakeSubHelper>());
+  MessageDeserializerPtr des(boost::make_shared<MessageDeserializer>(helper, SerializedMessage(), boost::shared_ptr<M_string>()));
 
   ASSERT_FALSE(queue.full());
 
@@ -164,8 +165,8 @@ TEST(SubscriptionQueue, clearCall)
 {
   SubscriptionQueue queue("blah", 1, false);
 
-  FakeSubHelperPtr helper(new FakeSubHelper);
-  MessageDeserializerPtr des(new MessageDeserializer(helper, SerializedMessage(), boost::shared_ptr<M_string>()));
+  FakeSubHelperPtr helper(boost::make_shared<FakeSubHelper>());
+  MessageDeserializerPtr des(boost::make_shared<MessageDeserializer>(helper, SerializedMessage(), boost::shared_ptr<M_string>()));
 
   queue.push(helper, des, false, VoidConstWPtr(), true);
   queue.clear();
@@ -176,8 +177,8 @@ TEST(SubscriptionQueue, clearThenAddAndCall)
 {
   SubscriptionQueue queue("blah", 1, false);
 
-  FakeSubHelperPtr helper(new FakeSubHelper);
-  MessageDeserializerPtr des(new MessageDeserializer(helper, SerializedMessage(), boost::shared_ptr<M_string>()));
+  FakeSubHelperPtr helper(boost::make_shared<FakeSubHelper>());
+  MessageDeserializerPtr des(boost::make_shared<MessageDeserializer>(helper, SerializedMessage(), boost::shared_ptr<M_string>()));
 
   queue.push(helper, des, false, VoidConstWPtr(), true);
   queue.clear();
@@ -194,8 +195,8 @@ TEST(SubscriptionQueue, clearInCallback)
 {
   SubscriptionQueue queue("blah", 1, false);
 
-  FakeSubHelperPtr helper(new FakeSubHelper);
-  MessageDeserializerPtr des(new MessageDeserializer(helper, SerializedMessage(), boost::shared_ptr<M_string>()));
+  FakeSubHelperPtr helper(boost::make_shared<FakeSubHelper>());
+  MessageDeserializerPtr des(boost::make_shared<MessageDeserializer>(helper, SerializedMessage(), boost::shared_ptr<M_string>()));
 
   helper->cb_ = boost::bind(clearInCallbackCallback, boost::ref(queue));
   queue.push(helper, des, false, VoidConstWPtr(), true);
@@ -218,8 +219,8 @@ TEST(SubscriptionQueue, clearWhileThreadIsBlocking)
 {
   SubscriptionQueue queue("blah", 1, false);
 
-  FakeSubHelperPtr helper(new FakeSubHelper);
-  MessageDeserializerPtr des(new MessageDeserializer(helper, SerializedMessage(), boost::shared_ptr<M_string>()));
+  FakeSubHelperPtr helper(boost::make_shared<FakeSubHelper>());
+  MessageDeserializerPtr des(boost::make_shared<MessageDeserializer>(helper, SerializedMessage(), boost::shared_ptr<M_string>()));
 
   bool done = false;
   boost::barrier barrier(2);
@@ -241,8 +242,8 @@ void waitForBarrier(boost::barrier* bar)
 TEST(SubscriptionQueue, concurrentCallbacks)
 {
   SubscriptionQueue queue("blah", 0, true);
-  FakeSubHelperPtr helper(new FakeSubHelper);
-  MessageDeserializerPtr des(new MessageDeserializer(helper, SerializedMessage(), boost::shared_ptr<M_string>()));
+  FakeSubHelperPtr helper(boost::make_shared<FakeSubHelper>());
+  MessageDeserializerPtr des(boost::make_shared<MessageDeserializer>(helper, SerializedMessage(), boost::shared_ptr<M_string>()));
 
   boost::barrier bar(2);
   helper->cb_ = boost::bind(waitForBarrier, &bar);
@@ -264,8 +265,8 @@ void waitForASecond()
 TEST(SubscriptionQueue, nonConcurrentOrdering)
 {
   SubscriptionQueue queue("blah", 0, false);
-  FakeSubHelperPtr helper(new FakeSubHelper);
-  MessageDeserializerPtr des(new MessageDeserializer(helper, SerializedMessage(), boost::shared_ptr<M_string>()));
+  FakeSubHelperPtr helper(boost::make_shared<FakeSubHelper>());
+  MessageDeserializerPtr des(boost::make_shared<MessageDeserializer>(helper, SerializedMessage(), boost::shared_ptr<M_string>()));
 
   helper->cb_ = waitForASecond;
   queue.push(helper, des, false, VoidConstWPtr(), true);
diff --git a/test/test_roscpp/test/test_transport_tcp.cpp b/test/test_roscpp/test/test_transport_tcp.cpp
index 9fe95d0..e8c8119 100644
--- a/test/test_roscpp/test/test_transport_tcp.cpp
+++ b/test/test_roscpp/test/test_transport_tcp.cpp
@@ -58,8 +58,8 @@ protected:
 
   virtual void SetUp()
   {
-    transports_[0] = TransportTCPPtr(new TransportTCP(NULL, TransportTCP::SYNCHRONOUS));
-    transports_[1] = TransportTCPPtr(new TransportTCP(NULL, TransportTCP::SYNCHRONOUS));
+    transports_[0] = boost::make_shared<TransportTCP>(static_cast<ros::PollSet*>(NULL), TransportTCP::SYNCHRONOUS);
+    transports_[1] = boost::make_shared<TransportTCP>(static_cast<ros::PollSet*>(NULL), TransportTCP::SYNCHRONOUS);
 
     if (!transports_[0]->listen(0, 100, TransportTCP::AcceptCallback()))
     {
@@ -251,8 +251,8 @@ protected:
     disconnected_[1] = false;
     disconnected_[2] = false;
 
-    transports_[0] = TransportTCPPtr(new TransportTCP(&poll_set_));
-    transports_[1] = TransportTCPPtr(new TransportTCP(&poll_set_));
+    transports_[0] = boost::make_shared<TransportTCP>(&poll_set_);
+    transports_[1] = boost::make_shared<TransportTCP>(&poll_set_);
 
     if (!transports_[0]->listen(0, 100, boost::bind(&Polled::connectionReceived, this, _1)))
     {
diff --git a/test/test_roscpp/test_serialization/CMakeLists.txt b/test/test_roscpp/test_serialization/CMakeLists.txt
index 3bc5c58..27e3517 100644
--- a/test/test_roscpp/test_serialization/CMakeLists.txt
+++ b/test/test_roscpp/test_serialization/CMakeLists.txt
@@ -5,23 +5,23 @@ endif()
 catkin_add_gtest(${PROJECT_NAME}-serialization src/serialization.cpp)
 if(TARGET ${PROJECT_NAME}-serialization)
   target_link_libraries(${PROJECT_NAME}-serialization ${catkin_LIBRARIES} ${GTEST_LIBRARIES})
-  add_dependencies(${PROJECT_NAME}-serialization ${PROJECT_NAME}_gencpp)
+  add_dependencies(${PROJECT_NAME}-serialization ${${PROJECT_NAME}_EXPORTED_TARGETS})
 endif()
 
 catkin_add_gtest(${PROJECT_NAME}-generated_messages src/generated_messages.cpp)
 if(TARGET ${PROJECT_NAME}-generated_messages)
   target_link_libraries(${PROJECT_NAME}-generated_messages ${catkin_LIBRARIES} ${GTEST_LIBRARIES})
-  add_dependencies(${PROJECT_NAME}-generated_messages ${PROJECT_NAME}_gencpp)
+  add_dependencies(${PROJECT_NAME}-generated_messages ${${PROJECT_NAME}_EXPORTED_TARGETS})
 endif()
 
 add_executable(${PROJECT_NAME}-builtin_types EXCLUDE_FROM_ALL src/builtin_types.cpp)
 add_dependencies(tests ${PROJECT_NAME}-builtin_types) 
 target_link_libraries(${PROJECT_NAME}-builtin_types ${catkin_LIBRARIES} ${GTEST_LIBRARIES})
-add_dependencies(${PROJECT_NAME}-builtin_types ${PROJECT_NAME}_gencpp)
+add_dependencies(${PROJECT_NAME}-builtin_types ${${PROJECT_NAME}_EXPORTED_TARGETS})
 add_rostest(test/builtin_types.test)
 
 add_executable(${PROJECT_NAME}-pre_deserialize EXCLUDE_FROM_ALL src/pre_deserialize.cpp)
 add_dependencies(tests ${PROJECT_NAME}-pre_deserialize)
 target_link_libraries(${PROJECT_NAME}-pre_deserialize ${catkin_LIBRARIES} ${GTEST_LIBRARIES})
-add_dependencies(${PROJECT_NAME}-pre_deserialize ${PROJECT_NAME}_gencpp)
+add_dependencies(${PROJECT_NAME}-pre_deserialize ${${PROJECT_NAME}_EXPORTED_TARGETS})
 add_rostest(test/pre_deserialize.test)
diff --git a/test/test_roscpp/test_serialization/src/helpers.h b/test/test_roscpp/test_serialization/src/helpers.h
index a30d967..833e21d 100644
--- a/test/test_roscpp/test_serialization/src/helpers.h
+++ b/test/test_roscpp/test_serialization/src/helpers.h
@@ -95,6 +95,7 @@ public:
   template<class U>
   Allocator(const Allocator<U>& u) throw ()
   {
+    (void)u;
   }
 
   ~Allocator() throw ()
@@ -115,10 +116,12 @@ public:
   }
   pointer allocate(size_type n, Allocator<void>::const_pointer hint = 0)
   {
+    (void)hint;
     return reinterpret_cast<pointer> (malloc(n * sizeof(T)));
   }
   void deallocate(pointer p, size_type n)
   {
+    (void)n;
     free(p);
   }
 
@@ -133,13 +136,13 @@ public:
 };
 
 template<class T1, class T2>
-inline bool operator==(const Allocator<T1>& a1, const Allocator<T2>& a2) throw ()
+inline bool operator==(const Allocator<T1>&, const Allocator<T2>&) throw ()
 {
   return true;
 }
 
 template<class T1, class T2>
-inline bool operator!=(const Allocator<T1>& a1, const Allocator<T2>& a2) throw ()
+inline bool operator!=(const Allocator<T1>&, const Allocator<T2>&) throw ()
 {
   return false;
 }
diff --git a/test/test_roscpp/test_serialization/src/pre_deserialize.cpp b/test/test_roscpp/test_serialization/src/pre_deserialize.cpp
index 83e7003..0ba5f5a 100644
--- a/test/test_roscpp/test_serialization/src/pre_deserialize.cpp
+++ b/test/test_roscpp/test_serialization/src/pre_deserialize.cpp
@@ -64,16 +64,16 @@ template<>
 struct Serializer<IncomingMsg>
 {
   template<typename Stream>
-  inline static void write(Stream& stream, const IncomingMsg& v)
+  inline static void write(Stream&, const IncomingMsg&)
   {
   }
 
   template<typename Stream>
-  inline static void read(Stream& stream, IncomingMsg& v)
+  inline static void read(Stream&, IncomingMsg&)
   {
   }
 
-  inline static uint32_t serializedLength(const IncomingMsg& v)
+  inline static uint32_t serializedLength(const IncomingMsg&)
   {
     return 0;
   }
@@ -83,16 +83,16 @@ template<>
 struct Serializer<OutgoingMsg>
 {
   template<typename Stream>
-  inline static void write(Stream& stream, const OutgoingMsg& v)
+  inline static void write(Stream&, const OutgoingMsg&)
   {
   }
 
   template<typename Stream>
-  inline static void read(Stream& stream, OutgoingMsg& v)
+  inline static void read(Stream&, OutgoingMsg&)
   {
   }
 
-  inline static uint32_t serializedLength(const OutgoingMsg& v)
+  inline static uint32_t serializedLength(const OutgoingMsg&)
   {
     return 0;
   }
diff --git a/test/test_roscpp/test_serialization/src/serialization.cpp b/test/test_roscpp/test_serialization/src/serialization.cpp
index f060a0b..aec015a 100644
--- a/test/test_roscpp/test_serialization/src/serialization.cpp
+++ b/test/test_roscpp/test_serialization/src/serialization.cpp
@@ -218,7 +218,7 @@ struct Serializer<FixedSizeSimple>
     deserialize(stream, v.a);
   }
 
-  inline static uint32_t serializedLength(const FixedSizeSimple& v)
+  inline static uint32_t serializedLength(const FixedSizeSimple&)
   {
     return 4;
   }
diff --git a/test/test_rosgraph/package.xml b/test/test_rosgraph/package.xml
index effdd77..1155be3 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.16</version>
+  <version>1.12.0</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 4570d09..12efcd0 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.16</version>
+  <version>1.12.0</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 50b66bc..5c5d01b 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.16</version>
+  <version>1.12.0</version>
   <description>
     Unit tests verifying that roslib is operating as expected.
   </description>
diff --git a/test/test_roslib_comm/test/setup.cfg b/test/test_roslib_comm/test/setup.cfg
deleted file mode 100644
index dc9b157..0000000
--- a/test/test_roslib_comm/test/setup.cfg
+++ /dev/null
@@ -1,4 +0,0 @@
-[nosetests]
-with-xunit=1
-with-coverage=1
-cover-package=roslib
diff --git a/test/test_rosmaster/package.xml b/test/test_rosmaster/package.xml
index c6a0f61..e55df88 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.16</version>
+  <version>1.12.0</version>
   <description>
     Tests for rosmaster which depend on rostest.
   </description>
diff --git a/test/test_rosmaster/test/setup.cfg b/test/test_rosmaster/test/setup.cfg
deleted file mode 100644
index 5530eba..0000000
--- a/test/test_rosmaster/test/setup.cfg
+++ /dev/null
@@ -1,4 +0,0 @@
-[nosetests]
-with-coverage=1
-cover-package=test_rosmaster
-with-xunit=1
diff --git a/test/test_rosparam/package.xml b/test/test_rosparam/package.xml
index e1109bb..fcc7397 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.16</version>
+  <version>1.12.0</version>
   <description>
     A package containing the unit tests for rosparam.
   </description>
diff --git a/test/test_rosparam/test/test_rosparam.py b/test/test_rosparam/test/check_rosparam.py
similarity index 95%
rename from test/test_rosparam/test/test_rosparam.py
rename to test/test_rosparam/test/check_rosparam.py
index 70ee061..52ed976 100755
--- a/test/test_rosparam/test/test_rosparam.py
+++ b/test/test_rosparam/test/check_rosparam.py
@@ -57,6 +57,14 @@ def fakestdout():
     yield fakestdout
     sys.stdout = realstdout
 
+ at contextmanager
+def fakestdin(input_str):
+    realstdin = sys.stdin
+    fakestdin = StringIO(input_str)
+    sys.stdin = fakestdin
+    yield fakestdin
+    sys.stdin = realstdin
+
 def tolist(b):
     return [x.strip() for x in b.getvalue().split('\n') if x.strip()]
 
@@ -141,6 +149,12 @@ class TestRosparam(unittest.TestCase):
         
         rosparam.yamlmain([cmd, 'load', '-v', f])
         self.assertEquals('bar', ps.getParam('/foo'))
+
+        # load into top-level from stdin
+        with fakestdin('stdin_string: stdin_foo\nstdin_string2: stdin_bar'):
+            rosparam.yamlmain([cmd, 'load', '-'])
+        self.assertEquals('stdin_foo', ps.getParam('/stdin_string'))
+        self.assertEquals('stdin_bar', ps.getParam('/stdin_string2'))
         
         # load into namespace
         rosparam.yamlmain([cmd, 'load', f, '/rosparam_load/test'])
@@ -339,6 +353,12 @@ class TestRosparam(unittest.TestCase):
             with open(f) as b2:
                 self.assertEquals(yaml.load(b.read()), yaml.load(b2.read()))
 
+        # yaml file and std_out should be the same
+        with fakestdout() as b:
+            rosparam.yamlmain([cmd, 'dump'])
+            with open(f) as b2:
+                self.assertEquals(yaml.load(b.getvalue())['rosparam_dump'], yaml.load(b2.read()))
+
     def test_fullusage(self):
         import rosparam
         try:
diff --git a/test/test_rosparam/test/test_rosparam_command_line_online.py b/test/test_rosparam/test/check_rosparam_command_line_online.py
similarity index 100%
rename from test/test_rosparam/test/test_rosparam_command_line_online.py
rename to test/test_rosparam/test/check_rosparam_command_line_online.py
diff --git a/test/test_rosparam/test/rosparam.test b/test/test_rosparam/test/rosparam.test
index bf64d2d..358df4f 100644
--- a/test/test_rosparam/test/rosparam.test
+++ b/test/test_rosparam/test/rosparam.test
@@ -15,6 +15,6 @@
     <param name="float" value="20.0" />
   </group>
   
-  <test test-name="rosparam_command_line_online" pkg="test_rosparam" type="test_rosparam_command_line_online.py" />
-  <test test-name="test_rosparam" pkg="test_rosparam" type="test_rosparam.py" />
+  <test test-name="rosparam_command_line_online" pkg="test_rosparam" type="check_rosparam_command_line_online.py" />
+  <test test-name="test_rosparam" pkg="test_rosparam" type="check_rosparam.py" />
 </launch>
diff --git a/test/test_rosparam/test/setup.cfg b/test/test_rosparam/test/setup.cfg
deleted file mode 100644
index f2b7980..0000000
--- a/test/test_rosparam/test/setup.cfg
+++ /dev/null
@@ -1,5 +0,0 @@
-[nosetests]
-with-coverage=1
-cover-package=rosparam
-with-xunit=1
-tests=test_rosparam_command_line_offline.py
diff --git a/test/test_rosparam/test/test_rosparam_command_line_offline.py b/test/test_rosparam/test/test_rosparam_command_line_offline.py
index c4842b1..d1e6644 100644
--- a/test/test_rosparam/test/test_rosparam_command_line_offline.py
+++ b/test/test_rosparam/test/test_rosparam_command_line_offline.py
@@ -70,7 +70,7 @@ class TestRosparamOffline(unittest.TestCase):
             self.assert_("%s %s"%(cmd, c) in output[0].decode(), "%s: %s" % (c, output[0].decode()))
             
         # test no args on commands that require args
-        for c in ['set', 'get', 'load', 'dump', 'delete']:
+        for c in ['set', 'get', 'load', 'delete']:
             output = Popen([cmd, c], stdout=PIPE, stderr=PIPE).communicate()
             self.assert_("Usage:" in output[0].decode() or "Usage:" in output[1].decode(), "%s\n%s"%(output, c))
             self.assert_("%s %s"%(cmd, c) in output[1].decode())
diff --git a/test/test_rospy/package.xml b/test/test_rospy/package.xml
index 418e40e..16b9f81 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.16</version>
+  <version>1.12.0</version>
   <description>
     rospy unit and integration test framework.
   </description>
diff --git a/test/test_rospy/test/unit/setup.cfg b/test/test_rospy/test/unit/setup.cfg
deleted file mode 100644
index 04d340b..0000000
--- a/test/test_rospy/test/unit/setup.cfg
+++ /dev/null
@@ -1,4 +0,0 @@
-[nosetests]
-with-coverage=1
-cover-package=rospy
-with-xunit=1
diff --git a/test/test_rospy/test/unit/test_rospy_numpy.py b/test/test_rospy/test/unit/test_rospy_numpy.py
index ad6367e..35c872c 100644
--- a/test/test_rospy/test/unit/test_rospy_numpy.py
+++ b/test/test_rospy/test/unit/test_rospy_numpy.py
@@ -78,3 +78,12 @@ class TestRospyNumpy(unittest.TestCase):
         self.assert_(isinstance(f3.data, numpy.ndarray), type(f3.data))
         v = numpy.equal(f3.data, numpy.array([1.0, 2.1, 3.2, 4.3, 5.4, 6.5], dtype=numpy.float32))
         self.assert_(v.all())
+
+    def test_class_identity(self):
+        from rospy.numpy_msg import numpy_msg
+        self.assert_(isinstance(numpy_msg(Floats)(), numpy_msg(Floats)))
+
+        FloatsNP = numpy_msg(Floats)
+        FloatsNP2 = numpy_msg(Floats)
+
+        self.assert_(FloatsNP is FloatsNP2)
diff --git a/test/test_rosservice/package.xml b/test/test_rosservice/package.xml
index 50d5851..694f9e8 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.16</version>
+  <version>1.12.0</version>
   <description>
     Tests for the rosservice tool.
   </description>
diff --git a/test/test_rosservice/test/test_rosservice.py b/test/test_rosservice/test/check_rosservice.py
similarity index 100%
rename from test/test_rosservice/test/test_rosservice.py
rename to test/test_rosservice/test/check_rosservice.py
diff --git a/test/test_rosservice/test/test_rosservice_command_line_online.py b/test/test_rosservice/test/check_rosservice_command_line_online.py
similarity index 100%
rename from test/test_rosservice/test/test_rosservice_command_line_online.py
rename to test/test_rosservice/test/check_rosservice_command_line_online.py
diff --git a/test/test_rosservice/test/rosservice.test b/test/test_rosservice/test/rosservice.test
index 955fc43..dcf2562 100644
--- a/test/test_rosservice/test/rosservice.test
+++ b/test/test_rosservice/test/rosservice.test
@@ -7,5 +7,5 @@
   <group ns="bar">
     <node name="a2iserver" pkg="test_rosmaster" type="add_two_ints_server" />
   </group>
-  <test test-name="rosservice_command_line_online" pkg="test_rosservice" type="test_rosservice_command_line_online.py" />
+  <test test-name="rosservice_command_line_online" pkg="test_rosservice" type="check_rosservice_command_line_online.py" />
 </launch>
diff --git a/test/test_rosservice/test/rosservice_unit.test b/test/test_rosservice/test/rosservice_unit.test
index db8d637..39ac477 100644
--- a/test/test_rosservice/test/rosservice_unit.test
+++ b/test/test_rosservice/test/rosservice_unit.test
@@ -7,5 +7,5 @@
   <group ns="bar">
     <node name="a2iserver" pkg="test_rosmaster" type="add_two_ints_server" />
   </group>
-  <test test-name="rosservice_unit" pkg="test_rosservice" type="test_rosservice.py" />
+  <test test-name="rosservice_unit" pkg="test_rosservice" type="check_rosservice.py" />
 </launch>
diff --git a/test/test_rosservice/test/setup.cfg b/test/test_rosservice/test/setup.cfg
deleted file mode 100644
index f9a5fb6..0000000
--- a/test/test_rosservice/test/setup.cfg
+++ /dev/null
@@ -1,3 +0,0 @@
-[nosetests]
-with-xunit=1
-tests=test_rosservice_command_line_offline.py
diff --git a/test/test_rostopic/package.xml b/test/test_rostopic/package.xml
index 2a09b5a..736c1d9 100644
--- a/test/test_rostopic/package.xml
+++ b/test/test_rostopic/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>test_rostopic</name>
-  <version>1.11.16</version>
+  <version>1.12.0</version>
   <description>
     Tests for rostopic.
   </description>
diff --git a/tools/rosbag/CHANGELOG.rst b/tools/rosbag/CHANGELOG.rst
index 217f1be..b1e8ab9 100644
--- a/tools/rosbag/CHANGELOG.rst
+++ b/tools/rosbag/CHANGELOG.rst
@@ -2,6 +2,17 @@
 Changelog for package rosbag
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.12.0 (2016-03-18)
+-------------------
+* add missing parameter to AdvertiseOptions::createAdvertiseOptions (`#733 <https://github.com/ros/ros_comm/issues/733>`_)
+
+1.11.18 (2016-03-17)
+--------------------
+
+1.11.17 (2016-03-11)
+--------------------
+* use boost::make_shared instead of new for constructing boost::shared_ptr (`#740 <https://github.com/ros/ros_comm/issues/740>`_)
+
 1.11.16 (2015-11-09)
 --------------------
 * show size unit for --size of rosbag record in help string (`#697 <https://github.com/ros/ros_comm/pull/697>`_)
diff --git a/tools/rosbag/CMakeLists.txt b/tools/rosbag/CMakeLists.txt
index 4d063ea..e821090 100644
--- a/tools/rosbag/CMakeLists.txt
+++ b/tools/rosbag/CMakeLists.txt
@@ -1,5 +1,10 @@
 cmake_minimum_required(VERSION 2.8.3)
 project(rosbag)
+
+if(NOT WIN32)
+  set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -Wextra")
+endif()
+
 find_package(catkin REQUIRED COMPONENTS rosbag_storage rosconsole roscpp topic_tools xmlrpcpp)
 find_package(Boost REQUIRED COMPONENTS date_time regex program_options filesystem)
 find_package(BZip2 REQUIRED)
diff --git a/tools/rosbag/include/rosbag/player.h b/tools/rosbag/include/rosbag/player.h
index 27ae999..3cb307b 100644
--- a/tools/rosbag/include/rosbag/player.h
+++ b/tools/rosbag/include/rosbag/player.h
@@ -59,10 +59,11 @@ namespace rosbag {
 /*!
  *  param msg         The Message instance for which to generate adveritse options
  *  param queue_size  The size of the outgoing queue
+ *  param prefix      An optional prefix for all output topics
  */
-ros::AdvertiseOptions createAdvertiseOptions(MessageInstance const& msg, uint32_t queue_size);
+ros::AdvertiseOptions createAdvertiseOptions(MessageInstance const& msg, uint32_t queue_size, const std::string& prefix = "");
 
-ROSBAG_DECL ros::AdvertiseOptions createAdvertiseOptions(const ConnectionInfo* c, uint32_t queue_size);
+ROSBAG_DECL ros::AdvertiseOptions createAdvertiseOptions(const ConnectionInfo* c, uint32_t queue_size, const std::string& prefix = "");
 
 
 struct ROSBAG_DECL PlayerOptions
diff --git a/tools/rosbag/package.xml b/tools/rosbag/package.xml
index 81958e6..971bcd1 100644
--- a/tools/rosbag/package.xml
+++ b/tools/rosbag/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>rosbag</name>
-  <version>1.11.16</version>
+  <version>1.12.0</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/player.cpp b/tools/rosbag/src/player.cpp
index 66d10e8..dd29341 100644
--- a/tools/rosbag/src/player.cpp
+++ b/tools/rosbag/src/player.cpp
@@ -103,10 +103,10 @@ void PlayerOptions::check() {
 Player::Player(PlayerOptions const& options) :
     options_(options),
     paused_(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)
+    pause_for_topics_(options_.pause_topics.size() > 0),
+    terminal_modified_(false)
 {
 }
 
@@ -126,7 +126,7 @@ void Player::publish() {
 
         try
         {
-            shared_ptr<Bag> bag(new Bag);
+            shared_ptr<Bag> bag(boost::make_shared<Bag>());
             bag->open(filename, bagmode::Read);
             bags_.push_back(bag);
         }
diff --git a/tools/rosbag/src/recorder.cpp b/tools/rosbag/src/recorder.cpp
index 19fc1f0..a6b7e26 100644
--- a/tools/rosbag/src/recorder.cpp
+++ b/tools/rosbag/src/recorder.cpp
@@ -209,19 +209,17 @@ shared_ptr<ros::Subscriber> Recorder::subscribe(string const& topic) {
 	ROS_INFO("Subscribing to %s", topic.c_str());
 
     ros::NodeHandle nh;
-    shared_ptr<int> count(new int(options_.limit));
-    shared_ptr<ros::Subscriber> sub(new ros::Subscriber);
+    shared_ptr<int> count(boost::make_shared<int>(options_.limit));
+    shared_ptr<ros::Subscriber> sub(boost::make_shared<ros::Subscriber>());
 
     ros::SubscribeOptions ops;
     ops.topic = topic;
     ops.queue_size = 100;
     ops.md5sum = ros::message_traits::md5sum<topic_tools::ShapeShifter>();
     ops.datatype = ros::message_traits::datatype<topic_tools::ShapeShifter>();
-    ops.helper = ros::SubscriptionCallbackHelperPtr(
-        new ros::SubscriptionCallbackHelperT<const ros::MessageEvent<topic_tools::ShapeShifter const>& >(
-            boost::bind(&Recorder::doQueue, this, _1, topic, sub, count)
-        )
-    );
+    ops.helper = boost::make_shared<ros::SubscriptionCallbackHelperT<
+        const ros::MessageEvent<topic_tools::ShapeShifter const> &> >(
+            boost::bind(&Recorder::doQueue, this, _1, topic, sub, count));
     *sub = nh.subscribe(ops);
 
     currently_recording_.insert(topic);
@@ -270,6 +268,7 @@ bool Recorder::shouldSubscribeToTopic(std::string const& topic, bool from_node)
 template<class T>
 std::string Recorder::timeToStr(T ros_t)
 {
+    (void)ros_t;
     std::stringstream msg;
     const boost::posix_time::ptime now=
         boost::posix_time::second_clock::local_time();
@@ -333,9 +332,9 @@ void Recorder::updateFilenames() {
     vector<string> parts;
 
     std::string prefix = options_.prefix;
-    uint32_t ind = prefix.rfind(".bag");
+    size_t ind = prefix.rfind(".bag");
 
-    if (ind != -1 && ind == prefix.size() - 4)
+    if (ind != std::string::npos && ind == prefix.size() - 4)
     {
       prefix.erase(ind);
     }
@@ -357,6 +356,7 @@ void Recorder::updateFilenames() {
 
 //! Callback to be invoked to actually do the recording
 void Recorder::snapshotTrigger(std_msgs::Empty::ConstPtr trigger) {
+    (void)trigger;
     updateFilenames();
     
     ROS_INFO("Triggered snapshot recording with name %s.", target_filename_.c_str());
@@ -537,6 +537,8 @@ void Recorder::doRecordSnapshotter() {
 }
 
 void Recorder::doCheckMaster(ros::TimerEvent const& e, ros::NodeHandle& node_handle) {
+    (void)e;
+    (void)node_handle;
     ros::master::V_TopicInfo topics;
     if (ros::master::getTopics(topics)) {
 		foreach(ros::master::TopicInfo const& t, topics) {
diff --git a/tools/rosbag_storage/CHANGELOG.rst b/tools/rosbag_storage/CHANGELOG.rst
index 87cb30b..bcae642 100644
--- a/tools/rosbag_storage/CHANGELOG.rst
+++ b/tools/rosbag_storage/CHANGELOG.rst
@@ -2,6 +2,17 @@
 Changelog for package rosbag_storage
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.12.0 (2016-03-18)
+-------------------
+
+1.11.18 (2016-03-17)
+--------------------
+* fix compiler warnings
+
+1.11.17 (2016-03-11)
+--------------------
+* use boost::make_shared instead of new for constructing boost::shared_ptr (`#740 <https://github.com/ros/ros_comm/issues/740>`_)
+
 1.11.16 (2015-11-09)
 --------------------
 
diff --git a/tools/rosbag_storage/CMakeLists.txt b/tools/rosbag_storage/CMakeLists.txt
index 4ceee01..5f64a1b 100644
--- a/tools/rosbag_storage/CMakeLists.txt
+++ b/tools/rosbag_storage/CMakeLists.txt
@@ -2,6 +2,10 @@ cmake_minimum_required(VERSION 2.8.3)
 
 project(rosbag_storage)
 
+if(NOT WIN32)
+  set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -Wextra")
+endif()
+
 find_package(console_bridge REQUIRED)
 find_package(catkin REQUIRED COMPONENTS cpp_common roscpp_serialization roscpp_traits rostime roslz4)
 find_package(Boost REQUIRED COMPONENTS date_time filesystem program_options regex)
diff --git a/tools/rosbag_storage/include/rosbag/bag.h b/tools/rosbag_storage/include/rosbag/bag.h
index 0702ad6..0696d72 100644
--- a/tools/rosbag_storage/include/rosbag/bag.h
+++ b/tools/rosbag_storage/include/rosbag/bag.h
@@ -403,7 +403,7 @@ boost::shared_ptr<T> Bag::instantiateBuffer(IndexEntry const& index_entry) const
             throw BagFormatException((boost::format("Unknown connection ID: %1%") % connection_id).str());
         ConnectionInfo* connection_info = connection_iter->second;
 
-        boost::shared_ptr<T> p = boost::shared_ptr<T>(new T());
+        boost::shared_ptr<T> p = boost::make_shared<T>();
 
         ros::serialization::PreDeserializeParams<T> predes_params;
         predes_params.message = p;
@@ -440,10 +440,10 @@ boost::shared_ptr<T> Bag::instantiateBuffer(IndexEntry const& index_entry) const
             throw BagFormatException((boost::format("Unknown connection ID: %1%") % connection_id).str());
         ConnectionInfo* connection_info = connection_iter->second;
 
-        boost::shared_ptr<T> p = boost::shared_ptr<T>(new T());
+        boost::shared_ptr<T> p = boost::make_shared<T>();
 
         // Create a new connection header, updated with the latching and callerid values
-        boost::shared_ptr<ros::M_string> message_header(new ros::M_string);
+        boost::shared_ptr<ros::M_string> message_header(boost::make_shared<ros::M_string>());
         for (ros::M_string::const_iterator i = connection_info->header->begin(); i != connection_info->header->end(); i++)
             (*message_header)[i->first] = i->second;
         (*message_header)["latching"] = latching;
@@ -534,7 +534,7 @@ void Bag::doWrite(std::string const& topic, ros::Time const& time, T const& msg,
                 connection_info->header = connection_header;
             }
             else {
-                connection_info->header = boost::shared_ptr<ros::M_string>(new ros::M_string);
+                connection_info->header = boost::make_shared<ros::M_string>();
                 (*connection_info->header)["type"]               = connection_info->datatype;
                 (*connection_info->header)["md5sum"]             = connection_info->md5sum;
                 (*connection_info->header)["message_definition"] = connection_info->msg_def;
diff --git a/tools/rosbag_storage/package.xml b/tools/rosbag_storage/package.xml
index d189cf7..c1a640e 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.16</version>
+  <version>1.12.0</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/rosbag_storage/src/bag.cpp b/tools/rosbag_storage/src/bag.cpp
index 2b961e6..62cd953 100644
--- a/tools/rosbag_storage/src/bag.cpp
+++ b/tools/rosbag_storage/src/bag.cpp
@@ -685,7 +685,7 @@ void Bag::readConnectionRecord() {
         ConnectionInfo* connection_info = new ConnectionInfo();
         connection_info->id       = id;
         connection_info->topic    = topic;
-        connection_info->header = shared_ptr<M_string>(new M_string);
+        connection_info->header = boost::make_shared<M_string>();
         for (M_string::const_iterator i = connection_header.getValues()->begin(); i != connection_header.getValues()->end(); i++)
             (*connection_info->header)[i->first] = i->second;
         connection_info->msg_def  = (*connection_info->header)["message_definition"];
@@ -733,7 +733,7 @@ void Bag::readMessageDefinitionRecord102() {
     connection_info->msg_def  = message_definition;
     connection_info->datatype = datatype;
     connection_info->md5sum   = md5sum;
-    connection_info->header = boost::shared_ptr<ros::M_string>(new ros::M_string);
+    connection_info->header = boost::make_shared<ros::M_string>();
     (*connection_info->header)["type"]               = connection_info->datatype;
     (*connection_info->header)["md5sum"]             = connection_info->md5sum;
     (*connection_info->header)["message_definition"] = connection_info->msg_def;
@@ -1024,6 +1024,7 @@ void Bag::readHeaderFromBuffer(Buffer& buffer, uint32_t offset, ros::Header& hea
 }
 
 void Bag::readMessageDataHeaderFromBuffer(Buffer& buffer, uint32_t offset, ros::Header& header, uint32_t& data_size, uint32_t& total_bytes_read) const {
+    (void)buffer;
     total_bytes_read = 0;
     uint8_t op = 0xFF;
     do {
diff --git a/tools/rosbag_storage/src/chunked_file.cpp b/tools/rosbag_storage/src/chunked_file.cpp
index 170afa7..0e90b02 100644
--- a/tools/rosbag_storage/src/chunked_file.cpp
+++ b/tools/rosbag_storage/src/chunked_file.cpp
@@ -37,6 +37,7 @@
 #include <iostream>
 
 #include <boost/format.hpp>
+#include <boost/make_shared.hpp>
 
 //#include <ros/ros.h>
 #ifdef _WIN32
@@ -67,7 +68,7 @@ ChunkedFile::ChunkedFile() :
     unused_(NULL),
     nUnused_(0)
 {
-    stream_factory_ = boost::shared_ptr<StreamFactory>(new StreamFactory(this));
+    stream_factory_ = boost::make_shared<StreamFactory>(this);
 }
 
 ChunkedFile::~ChunkedFile() {
@@ -116,8 +117,8 @@ void ChunkedFile::open(string const& filename, string const& mode) {
     if (!file_)
         throw BagIOException((format("Error opening file: %1%") % filename.c_str()).str());
 
-    read_stream_  = shared_ptr<Stream>(new UncompressedStream(this));
-    write_stream_ = shared_ptr<Stream>(new UncompressedStream(this));
+    read_stream_  = boost::make_shared<UncompressedStream>(this);
+    write_stream_ = boost::make_shared<UncompressedStream>(this);
     filename_     = filename;
     offset_       = ftello(file_);
 }
diff --git a/tools/rosbag_storage/src/lz4_stream.cpp b/tools/rosbag_storage/src/lz4_stream.cpp
index 8591517..9502664 100644
--- a/tools/rosbag_storage/src/lz4_stream.cpp
+++ b/tools/rosbag_storage/src/lz4_stream.cpp
@@ -101,7 +101,7 @@ void LZ4Stream::writeStream(int action) {
         // If output data is ready, write to disk
         int to_write = lz4s_.output_next - buff_;
         if (to_write > 0) {
-            if (fwrite(buff_, 1, to_write, getFilePointer()) != to_write) {
+            if (fwrite(buff_, 1, to_write, getFilePointer()) != static_cast<size_t>(to_write)) {
                 throw BagException("Problem writing data to disk");
             }
             advanceOffset(to_write);
diff --git a/tools/rosconsole/CHANGELOG.rst b/tools/rosconsole/CHANGELOG.rst
index 82ed9c0..01ab8f9 100644
--- a/tools/rosconsole/CHANGELOG.rst
+++ b/tools/rosconsole/CHANGELOG.rst
@@ -2,6 +2,18 @@
 Changelog for package rosconsole
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.12.0 (2016-03-18)
+-------------------
+* make LogAppender and Token destructor virtual (`#729 <https://github.com/ros/ros_comm/issues/729>`_)
+
+1.11.18 (2016-03-17)
+--------------------
+* fix compiler warnings
+
+1.11.17 (2016-03-11)
+--------------------
+* use boost::make_shared instead of new for constructing boost::shared_ptr (`#740 <https://github.com/ros/ros_comm/issues/740>`_)
+
 1.11.16 (2015-11-09)
 --------------------
 
diff --git a/tools/rosconsole/CMakeLists.txt b/tools/rosconsole/CMakeLists.txt
index f7a4c00..b31a9d6 100644
--- a/tools/rosconsole/CMakeLists.txt
+++ b/tools/rosconsole/CMakeLists.txt
@@ -1,6 +1,10 @@
 cmake_minimum_required(VERSION 2.8.3)
 project(rosconsole)
 
+if(NOT WIN32)
+  set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -Wextra")
+endif()
+
 find_package(catkin REQUIRED COMPONENTS cpp_common rostime rosunit)
 
 find_package(Boost COMPONENTS regex system thread)
diff --git a/tools/rosconsole/include/ros/console.h b/tools/rosconsole/include/ros/console.h
index 793e64d..4d2a86b 100644
--- a/tools/rosconsole/include/ros/console.h
+++ b/tools/rosconsole/include/ros/console.h
@@ -100,6 +100,8 @@ class LogAppender
 {
 public:
 
+  virtual ~LogAppender() {}
+
   virtual void log(::ros::console::Level level, const char* str, const char* file, const char* function, int line) = 0;
 
 };
@@ -108,6 +110,7 @@ ROSCONSOLE_DECL void register_appender(LogAppender* appender);
 
 struct Token
 {
+  virtual ~Token() {}
   /*
    * @param level
    * @param message
diff --git a/tools/rosconsole/package.xml b/tools/rosconsole/package.xml
index 1b22d0b..a41eba7 100644
--- a/tools/rosconsole/package.xml
+++ b/tools/rosconsole/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>rosconsole</name>
-  <version>1.11.16</version>
+  <version>1.12.0</version>
   <description>ROS console output library.</description>
   <maintainer email="dthomas at osrfoundation.org">Dirk Thomas</maintainer>
   <license>BSD</license>
diff --git a/tools/rosconsole/src/rosconsole/impl/rosconsole_log4cxx.cpp b/tools/rosconsole/src/rosconsole/impl/rosconsole_log4cxx.cpp
index 8fe601c..96a4ed6 100644
--- a/tools/rosconsole/src/rosconsole/impl/rosconsole_log4cxx.cpp
+++ b/tools/rosconsole/src/rosconsole/impl/rosconsole_log4cxx.cpp
@@ -305,6 +305,7 @@ public:
 protected:
   virtual void append(const log4cxx::spi::LoggingEventPtr& event, log4cxx::helpers::Pool& pool)
   {
+    (void)pool;
     levels::Level level;
     if (event->getLevel() == log4cxx::Level::getFatal())
     {
diff --git a/tools/rosconsole/src/rosconsole/rosconsole.cpp b/tools/rosconsole/src/rosconsole/rosconsole.cpp
index f8108f6..1331ae1 100644
--- a/tools/rosconsole/src/rosconsole/rosconsole.cpp
+++ b/tools/rosconsole/src/rosconsole/rosconsole.cpp
@@ -40,6 +40,7 @@
 #include <boost/thread.hpp>
 #include <boost/shared_array.hpp>
 #include <boost/regex.hpp>
+#include <boost/make_shared.hpp>
 
 #include <cstdarg>
 #include <cstdlib>
@@ -160,6 +161,10 @@ struct SeverityToken : public Token
 {
   virtual std::string getString(void*, ::ros::console::Level level, const char* str, const char* file, const char* function, int line)
   {
+    (void)str;
+    (void)file;
+    (void)function;
+    (void)line;
     if (level == levels::Fatal)
     {
       return "FATAL";
@@ -224,6 +229,11 @@ struct LoggerToken : public Token
 {
   virtual std::string getString(void* logger_handle, ::ros::console::Level level, const char* str, const char* file, const char* function, int line)
   {
+    (void)level;
+    (void)str;
+    (void)file;
+    (void)function;
+    (void)line;
     return ::ros::console::impl::getName(logger_handle);
   }
 };
@@ -258,38 +268,38 @@ TokenPtr createTokenFromType(const std::string& type)
 {
   if (type == "severity")
   {
-    return TokenPtr(new SeverityToken());
+    return TokenPtr(boost::make_shared<SeverityToken>());
   }
   else if (type == "message")
   {
-    return TokenPtr(new MessageToken());
+    return TokenPtr(boost::make_shared<MessageToken>());
   }
   else if (type == "time")
   {
-    return TokenPtr(new TimeToken());
+    return TokenPtr(boost::make_shared<TimeToken>());
   }
   else if (type == "thread")
   {
-    return TokenPtr(new ThreadToken());
+    return TokenPtr(boost::make_shared<ThreadToken>());
   }
   else if (type == "logger")
   {
-    return TokenPtr(new LoggerToken());
+    return TokenPtr(boost::make_shared<LoggerToken>());
   }
   else if (type == "file")
   {
-    return TokenPtr(new FileToken());
+    return TokenPtr(boost::make_shared<FileToken>());
   }
   else if (type == "line")
   {
-    return TokenPtr(new LineToken());
+    return TokenPtr(boost::make_shared<LineToken>());
   }
   else if (type == "function")
   {
-    return TokenPtr(new FunctionToken());
+    return TokenPtr(boost::make_shared<FunctionToken>());
   }
 
-  return TokenPtr(new FixedMapToken(type));
+  return TokenPtr(boost::make_shared<FixedMapToken>(type));
 }
 
 void Formatter::init(const char* fmt)
@@ -314,7 +324,7 @@ void Formatter::init(const char* fmt)
 
     std::string token = results[1];
     last_suffix = results.suffix();
-    tokens_.push_back(TokenPtr(new FixedToken(results.prefix())));
+    tokens_.push_back(TokenPtr(boost::make_shared<FixedToken>(results.prefix())));
     tokens_.push_back(createTokenFromType(token));
 
     start = results[0].second;
@@ -323,11 +333,11 @@ void Formatter::init(const char* fmt)
 
   if (matched_once)
   {
-    tokens_.push_back(TokenPtr(new FixedToken(last_suffix)));
+    tokens_.push_back(TokenPtr(boost::make_shared<FixedToken>(last_suffix)));
   }
   else
   {
-    tokens_.push_back(TokenPtr(new FixedToken(format_)));
+    tokens_.push_back(TokenPtr(boost::make_shared<FixedToken>(format_)));
   }
 }
 
diff --git a/tools/rosconsole/test/thread_test.cpp b/tools/rosconsole/test/thread_test.cpp
index b5e0523..14de2b8 100644
--- a/tools/rosconsole/test/thread_test.cpp
+++ b/tools/rosconsole/test/thread_test.cpp
@@ -53,7 +53,7 @@ public:
   V_Info info_;
 
 protected:
-  virtual void append(const log4cxx::spi::LoggingEventPtr& event, log4cxx::helpers::Pool& pool)
+  virtual void append(const log4cxx::spi::LoggingEventPtr& event, log4cxx::helpers::Pool&)
   {
     Info info;
     info.level_ = event->getLevel();
diff --git a/tools/rosconsole/test/utest.cpp b/tools/rosconsole/test/utest.cpp
index 47e8552..17fdfd4 100644
--- a/tools/rosconsole/test/utest.cpp
+++ b/tools/rosconsole/test/utest.cpp
@@ -54,7 +54,7 @@ public:
   V_Info info_;
 
 protected:
-  virtual void append(const log4cxx::spi::LoggingEventPtr& event, log4cxx::helpers::Pool& pool)
+  virtual void append(const log4cxx::spi::LoggingEventPtr& event, log4cxx::helpers::Pool&)
   {
     Info info;
     info.level_ = event->getLevel();
@@ -76,7 +76,7 @@ protected:
 class TestAppenderWithThrow : public log4cxx::AppenderSkeleton
 {
 protected:
-  virtual void append(const log4cxx::spi::LoggingEventPtr& event, log4cxx::helpers::Pool& pool)
+  virtual void append(const log4cxx::spi::LoggingEventPtr&, log4cxx::helpers::Pool&)
   {
     throw std::runtime_error("This should be caught");
   }
diff --git a/tools/rosgraph/CHANGELOG.rst b/tools/rosgraph/CHANGELOG.rst
index db2b3f5..a15164e 100644
--- a/tools/rosgraph/CHANGELOG.rst
+++ b/tools/rosgraph/CHANGELOG.rst
@@ -2,6 +2,18 @@
 Changelog for package rosgraph
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.12.0 (2016-03-18)
+-------------------
+
+1.11.18 (2016-03-17)
+--------------------
+
+1.11.17 (2016-03-11)
+--------------------
+* fix raising classes not derived from `Exception` which caused a TypeError (`#761 <https://github.com/ros/ros_comm/pull/761>`_)
+* fix handshake header with Python 3 (`#759 <https://github.com/ros/ros_comm/issues/759>`_)
+* fix encoding of header fields (`#704 <https://github.com/ros/ros_comm/issues/704>`_)
+
 1.11.16 (2015-11-09)
 --------------------
 
diff --git a/tools/rosgraph/package.xml b/tools/rosgraph/package.xml
index 9c90915..cafd2f0 100644
--- a/tools/rosgraph/package.xml
+++ b/tools/rosgraph/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>rosgraph</name>
-  <version>1.11.16</version>
+  <version>1.12.0</version>
   <description>
     rosgraph contains the rosgraph command-line tool, which prints
     information about the ROS Computation Graph. It also provides an
diff --git a/tools/rosgraph/src/rosgraph/network.py b/tools/rosgraph/src/rosgraph/network.py
index ff49991..7e7cd57 100644
--- a/tools/rosgraph/src/rosgraph/network.py
+++ b/tools/rosgraph/src/rosgraph/network.py
@@ -393,19 +393,19 @@ def encode_ros_handshake_header(header):
     FORMAT: (4-byte length + [4-byte field length + field=value ]*)
 
     :param header: header field keys/values, ``dict``
-    :returns: header encoded as byte string, ``str``
-    """    
-    fields = ["%s=%s" % (k, header[k]) for k in sorted(header.keys())]
+    :returns: header encoded as byte string, ``bytes``
+    """
+    str_cls = str if python3 else unicode
     
-    # in the usual configuration, the error 'TypeError: can't concat bytes to str' appears:
-    if python3 == 0:
-        #python 2
-        s = ''.join(["%s%s"%(struct.pack('<I', len(f)), f) for f in fields])
-        return struct.pack('<I', len(s)) + s
-    else:
-        #python 3 
-        s = b''.join([(struct.pack('<I', len(f)) + f.encode("utf-8")) for f in fields])
-        return struct.pack('<I', len(s)) + s
+    # encode all unicode keys in the header. Ideally, the type of these would be specified by the api
+    for k, v in sorted(header.items()):
+        if isinstance(k, str_cls): k = k.encode('utf-8')
+        if isinstance(v, str_cls): v = v.encode('utf-8')
+    
+    fields = [k + b"=" + v for k, v in sorted(header.items())]
+    s = b''.join([struct.pack('<I', len(f)) + f for f in fields])
+    
+    return struct.pack('<I', len(s)) + s
                                         
 def write_ros_handshake_header(sock, header):
     """
diff --git a/tools/rosgraph/src/rosgraph/roslogging.py b/tools/rosgraph/src/rosgraph/roslogging.py
index ea48aef..02a0bcc 100644
--- a/tools/rosgraph/src/rosgraph/roslogging.py
+++ b/tools/rosgraph/src/rosgraph/roslogging.py
@@ -43,7 +43,7 @@ import logging.config
 import rospkg
 from rospkg.environment import ROS_LOG_DIR
 
-class LoggingException: pass
+class LoggingException(Exception): pass
 
 def renew_latest_logdir(logfile_dir):
     log_dir = os.path.dirname(logfile_dir)
diff --git a/tools/rosgraph/test/setup.cfg b/tools/rosgraph/test/setup.cfg
deleted file mode 100644
index 45af5c2..0000000
--- a/tools/rosgraph/test/setup.cfg
+++ /dev/null
@@ -1,4 +0,0 @@
-[nosetests]
-with-coverage=1
-cover-package=rosgraph
-with-xunit=1
diff --git a/tools/roslaunch/CHANGELOG.rst b/tools/roslaunch/CHANGELOG.rst
index f2c8ebb..a716572 100644
--- a/tools/roslaunch/CHANGELOG.rst
+++ b/tools/roslaunch/CHANGELOG.rst
@@ -2,6 +2,19 @@
 Changelog for package roslaunch
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.12.0 (2016-03-18)
+-------------------
+
+1.11.18 (2016-03-17)
+--------------------
+
+1.11.17 (2016-03-11)
+--------------------
+* improve roslaunch-check to not fail if recursive dependencies lack dependencies (`#730 <https://github.com/ros/ros_comm/pull/730>`_)
+* add "pass_all_args" attribute to roslaunch "include" tag (`#710 <https://github.com/ros/ros_comm/pull/710>`_)
+* fix a typo in unknown host error message (`#735 <https://github.com/ros/ros_comm/pull/735>`_)
+* wait for param server to be available before trying to get param (`#711 <https://github.com/ros/ros_comm/pull/711>`_)
+
 1.11.16 (2015-11-09)
 --------------------
 * add `-w` and `-t` options (`#687 <https://github.com/ros/ros_comm/pull/687>`_)
diff --git a/tools/roslaunch/package.xml b/tools/roslaunch/package.xml
index a65713f..9b0664c 100644
--- a/tools/roslaunch/package.xml
+++ b/tools/roslaunch/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>roslaunch</name>
-  <version>1.11.16</version>
+  <version>1.12.0</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/roslaunch/src/roslaunch/core.py b/tools/roslaunch/src/roslaunch/core.py
index 6c51e6b..a6d43e3 100644
--- a/tools/roslaunch/src/roslaunch/core.py
+++ b/tools/roslaunch/src/roslaunch/core.py
@@ -247,7 +247,7 @@ def remap_localhost_uri(uri, force_localhost=False):
 ##################################################################
 # DATA STRUCTURES
 
-class Master:
+class Master(object):
     """
     Data structure for representing and querying state of master 
     """
diff --git a/tools/roslaunch/src/roslaunch/loader.py b/tools/roslaunch/src/roslaunch/loader.py
index ae7aaec..db8e6c7 100644
--- a/tools/roslaunch/src/roslaunch/loader.py
+++ b/tools/roslaunch/src/roslaunch/loader.py
@@ -172,6 +172,8 @@ class LoaderContext(object):
         self.arg_names = arg_names or []
         # special scoped resolve dict for processing in <include> tag
         self.include_resolve_dict = include_resolve_dict or None
+        # when this context was created via include, was pass_all_args set?
+        self.pass_all_args = False
 
     def add_param(self, p):
         """
@@ -214,8 +216,11 @@ class LoaderContext(object):
         Add 'arg' to existing context. Args are only valid for their immediate context.
         """
         if name in self.arg_names:
-            raise LoadException("arg '%s' has already been declared"%name)
-        self.arg_names.append(name)
+            # Ignore the duplication if pass_all_args was set
+            if not self.pass_all_args:
+                raise LoadException("arg '%s' has already been declared"%name)
+        else:
+            self.arg_names.append(name)
 
         resolve_dict = self.resolve_dict if self.include_resolve_dict is None else self.include_resolve_dict
 
@@ -228,7 +233,9 @@ class LoaderContext(object):
         if value is not None:
             # value is set, error if declared in our arg dict as args
             # with set values are constant/grounded.
-            if name in arg_dict:
+            # But don't error if pass_all_args was used to include this
+            # context; rather just override the passed-in value.
+            if name in arg_dict and not self.pass_all_args:
                 raise LoadException("cannot override arg '%s', which has already been set"%name)
             arg_dict[name] = value
         elif default is not None:
diff --git a/tools/roslaunch/src/roslaunch/remoteprocess.py b/tools/roslaunch/src/roslaunch/remoteprocess.py
index 33eeff6..1f6d65e 100644
--- a/tools/roslaunch/src/roslaunch/remoteprocess.py
+++ b/tools/roslaunch/src/roslaunch/remoteprocess.py
@@ -120,7 +120,7 @@ Please manually:
 then try roslaunching again.
 
 If you wish to configure roslaunch to automatically recognize unknown
-hosts, please set the environment variable ROSLAUNCH_SSH_UNKNOWN=1"""%(resolved_address, user_str, port_str, resolved_address)
+hosts, please set the environment variable ROSLAUNCH_SSH_UNKNOWN=1"""%(resolved_address, port_str, user_str, resolved_address)
         
 class SSHChildROSLaunchProcess(roslaunch.server.ChildROSLaunchProcess):
     """
diff --git a/tools/roslaunch/src/roslaunch/rlutil.py b/tools/roslaunch/src/roslaunch/rlutil.py
index 63b796c..9d4300a 100644
--- a/tools/roslaunch/src/roslaunch/rlutil.py
+++ b/tools/roslaunch/src/roslaunch/rlutil.py
@@ -193,6 +193,7 @@ def check_roslaunch(f):
     except roslaunch.core.RLException as e:
         return str(e)
     
+    rospack = rospkg.RosPack()
     errors = []
     # check for missing deps
     try:
@@ -206,8 +207,21 @@ def check_roslaunch(f):
         missing = {}
         file_deps = {}
     for pkg, miss in missing.items():
-        if miss:
+        # even if the pkgs is not found in packges.xml, if other package.xml provdes that pkgs, then it will be ok
+        all_pkgs = []
+        try:
+            for file_dep in file_deps.keys():
+                file_pkg = rospkg.get_package_name(file_dep)
+                all_pkgs.extend(rospack.get_depends(file_pkg,implicit=False))
+                miss_all = list(set(miss) - set(all_pkgs))
+        except Exception as e:
+            print(e, file=sys.stderr)
+            miss_all = True
+        if miss_all:
+            print("Missing package dependencies: %s/package.xml: %s"%(pkg, ', '.join(miss)), file=sys.stderr)
             errors.append("Missing package dependencies: %s/package.xml: %s"%(pkg, ', '.join(miss)))
+        elif miss:
+            print("Missing package dependencies: %s/package.xml: %s (notify upstream maintainer)"%(pkg, ', '.join(miss)), file=sys.stderr)
     
     # load all node defs
     nodes = []
@@ -215,7 +229,6 @@ def check_roslaunch(f):
         nodes.extend(rldeps.nodes)
 
     # check for missing packages
-    rospack = rospkg.RosPack()
     for pkg, node_type in nodes:
         try:
             rospack.get_path(pkg)
diff --git a/tools/roslaunch/src/roslaunch/scriptapi.py b/tools/roslaunch/src/roslaunch/scriptapi.py
index f8184bc..5a688ee 100644
--- a/tools/roslaunch/src/roslaunch/scriptapi.py
+++ b/tools/roslaunch/src/roslaunch/scriptapi.py
@@ -58,7 +58,7 @@ class ROSLaunch(object):
         """
         import rosgraph.masterapi
         master = rosgraph.masterapi.Master('/roslaunch_script')
-        uuid = master.getParam('/run_id')
+        uuid = roslaunch.rlutil.get_or_generate_uuid(None, True)
         self.parent = roslaunch.parent.ROSLaunchParent(uuid, [], is_core=False)
         self.started = False
 
diff --git a/tools/roslaunch/src/roslaunch/xmlloader.py b/tools/roslaunch/src/roslaunch/xmlloader.py
index 6714615..ff07ff4 100644
--- a/tools/roslaunch/src/roslaunch/xmlloader.py
+++ b/tools/roslaunch/src/roslaunch/xmlloader.py
@@ -580,14 +580,30 @@ class XmlLoader(loader.Loader):
             else:
                 ros_config.add_config_error("Deprecation Warning: "+deprecated)
 
-    INCLUDE_ATTRS = ('file', NS, CLEAR_PARAMS)
+    INCLUDE_ATTRS = ('file', NS, CLEAR_PARAMS, 'pass_all_args')
     @ifunless
     def _include_tag(self, tag, context, ros_config, default_machine, is_core, verbose):
         self._check_attrs(tag, context, ros_config, XmlLoader.INCLUDE_ATTRS)
         inc_filename = self.resolve_args(tag.attributes['file'].value, context)
 
+        if tag.hasAttribute('pass_all_args'):
+            pass_all_args = self.resolve_args(tag.attributes['pass_all_args'].value, context)
+            pass_all_args = _bool_attr(pass_all_args, False, 'pass_all_args')
+        else:
+            pass_all_args = False
+
         child_ns = self._ns_clear_params_attr(tag.tagName, tag, context, ros_config, include_filename=inc_filename)
 
+        # If we're asked to pass all args, then we need to add them into the
+        # child context.
+        if pass_all_args:
+            if 'arg' in context.resolve_dict:
+                for name, value in context.resolve_dict['arg'].items():
+                    child_ns.add_arg(name, value=value)
+            # Also set the flag that tells the child context to ignore (rather than
+            # error on) attempts to set the same arg twice.
+            child_ns.pass_all_args = True
+
         for t in [c for c in tag.childNodes if c.nodeType == DomNode.ELEMENT_NODE]:
             tag_name = t.tagName.lower()
             if tag_name == 'env':
diff --git a/tools/roslaunch/test/unit/setup.cfg b/tools/roslaunch/test/unit/setup.cfg
deleted file mode 100644
index a5077db..0000000
--- a/tools/roslaunch/test/unit/setup.cfg
+++ /dev/null
@@ -1,5 +0,0 @@
-[nosetests]
-with-coverage=1
-cover-package=roslaunch
-with-xunit=1
-tests=test_core.py, test_nodeprocess.py, test_roslaunch_child.py, test_roslaunch_core.py, test_roslaunch_depends.py, test_roslaunch_dump_params.py, test_roslaunch_launch.py, test_roslaunch_list_files.py, test_roslaunch_param_dump.py, test_roslaunch_parent.py, test_roslaunch_pmon.py, test_roslaunch_remote.py, test_roslaunch_rlutil.py, test_roslaunch_server.py, test_substitution_args.py, test_xmlloader.py
diff --git a/tools/roslaunch/test/unit/test_roslaunch_dump_params.py b/tools/roslaunch/test/unit/test_roslaunch_dump_params.py
old mode 100755
new mode 100644
diff --git a/tools/roslaunch/test/unit/test_xmlloader.py b/tools/roslaunch/test/unit/test_xmlloader.py
old mode 100755
new mode 100644
index 002bb38..0ffab6c
--- a/tools/roslaunch/test/unit/test_xmlloader.py
+++ b/tools/roslaunch/test/unit/test_xmlloader.py
@@ -938,4 +938,115 @@ class TestXmlLoader(unittest.TestCase):
         self.assertEquals(param_d['/include3/include_test/p3_test'], 'set')
         self.assertEquals(param_d['/include3/include_test/p4_test'], 'new3')
         
+    # Test the new attribute <include pass_all_args={"true"|"false"}>
+    def test_arg_all(self):
+        loader = roslaunch.xmlloader.XmlLoader()
+        filename = os.path.join(self.xml_dir, 'test-arg-all.xml')
+
+        # Test suite A: load without an optional arg set externally
+        mock = RosLaunchMock()
+        loader.load(filename, mock, argv=["required:=test_arg"])
+
+        param_d = {}
+        for p in mock.params:
+            param_d[p.key] = p.value
+
+        # Sanity check: Parent namespace
+        self.assertEquals(param_d['/p1_test'], 'test_arg')
+        self.assertEquals(param_d['/p2_test'], 'not_set')
+        self.assertEquals(param_d['/p3_test'], 'parent')
+
+        # Test case 1: include without pass_all_args
+        self.assertEquals(param_d['/notall/include_test/p1_test'], 'test_arg')
+        self.assertEquals(param_d['/notall/include_test/p2_test'], 'not_set')
+        self.assertEquals(param_d['/notall/include_test/p3_test'], 'set')
+
+        # Test case 2: include without pass_all_args attribute, and pass optional arg
+        # internally
+        self.assertEquals(param_d['/notall_optional/include_test/p1_test'], 'test_arg')
+        self.assertEquals(param_d['/notall_optional/include_test/p2_test'], 'not_set')
+        self.assertEquals(param_d['/notall_optional/include_test/p3_test'], 'set')
+
+        # Test case 3: include with pass_all_args attribute, instead of passing individual
+        # args
+        self.assertEquals(param_d['/all/include_test/p1_test'], 'test_arg')
+        self.assertEquals(param_d['/all/include_test/p2_test'], 'not_set')
+        self.assertEquals(param_d['/all/include_test/p3_test'], 'set')
+
+        # Test case 4: include with pass_all_args attribute, and override one
+        # arg inside the include tag
+        self.assertEquals(param_d['/all_override/include_test/p1_test'], 'override')
+        self.assertEquals(param_d['/all_override/include_test/p2_test'], 'not_set')
+        self.assertEquals(param_d['/all_override/include_test/p3_test'], 'set')
+
+        # Test suite B: load with an optional arg set externally
+        mock = RosLaunchMock()
+        loader.load(filename, mock, argv=["required:=test_arg", "optional:=test_arg2"])
+
+        param_d = {}
+        for p in mock.params:
+            param_d[p.key] = p.value
+
+        # Sanity check: Parent namespace
+        self.assertEquals(param_d['/p1_test'], 'test_arg')
+        self.assertEquals(param_d['/p2_test'], 'test_arg2')
+        self.assertEquals(param_d['/p3_test'], 'parent')
+
+        # Test case 1: include without pass_all_args attribute
+        self.assertEquals(param_d['/notall/include_test/p1_test'], 'test_arg')
+        self.assertEquals(param_d['/notall/include_test/p2_test'], 'not_set')
+        self.assertEquals(param_d['/notall/include_test/p3_test'], 'set')
+
+        # Test case 2: include without pass_all_args attribute, and pass optional arg
+        # internally
+        self.assertEquals(param_d['/notall_optional/include_test/p1_test'], 'test_arg')
+        self.assertEquals(param_d['/notall_optional/include_test/p2_test'], 'test_arg2')
+        self.assertEquals(param_d['/notall_optional/include_test/p3_test'], 'set')
+
+        # Test case 3: include with pass_all_args attribute, instead of passing individual
+        # args
+        self.assertEquals(param_d['/all/include_test/p1_test'], 'test_arg')
+        self.assertEquals(param_d['/all/include_test/p2_test'], 'test_arg2')
+        self.assertEquals(param_d['/all/include_test/p3_test'], 'set')
+
+        # Test case 4: include with pass_all_args attribute, and override one
+        # arg inside the include tag
+        self.assertEquals(param_d['/all_override/include_test/p1_test'], 'override')
+        self.assertEquals(param_d['/all_override/include_test/p2_test'], 'test_arg2')
+        self.assertEquals(param_d['/all_override/include_test/p3_test'], 'set')
+
+    def test_arg_all_includes(self):
+        loader = roslaunch.xmlloader.XmlLoader()
+        # Test 1:
+        # Can't explicitly set an arg when including a file that sets the same
+        # arg as constant.
+        mock = RosLaunchMock()
+        filename = os.path.join(self.xml_dir, 'test-arg-invalid-include.xml')
+        try:
+            loader.load(filename, mock)            
+            self.fail('should have thrown an exception')
+        except roslaunch.xmlloader.XmlParseException:
+            pass
 
+        # Test 2:
+        # Can have arg set in parent launch file, then include a file that sets
+        # it constant, with pass_all_args="true"
+        mock = RosLaunchMock()
+        filename = os.path.join(self.xml_dir, 'test-arg-valid-include.xml')
+        # Just make sure there's no exception
+        loader.load(filename, mock)            
+
+        # This test checks for exception behavior that would be nice to have,
+        # but would require intrusive changes to how roslaunch passes arguments
+        # to included contexts. It currently fails. I'm leaving it here as a
+        # reference for potential future work.
+        ## Test 3:
+        ## Can't do explicit override of arg during inclusion of file that sets
+        ## it constant, even when pass_all_args="true"
+        #mock = RosLaunchMock()
+        #filename = os.path.join(self.xml_dir, 'test-arg-invalid-include2.xml')
+        #try:
+        #    loader.load(filename, mock)            
+        #    self.fail('should have thrown an exception')
+        #except roslaunch.xmlloader.XmlParseException:
+        #    pass
diff --git a/tools/roslaunch/test/xml/test-arg-all.xml b/tools/roslaunch/test/xml/test-arg-all.xml
new file mode 100644
index 0000000..4f3aa23
--- /dev/null
+++ b/tools/roslaunch/test/xml/test-arg-all.xml
@@ -0,0 +1,48 @@
+<launch>
+
+  <arg name="required" />
+  <arg name="optional" default="not_set" />
+  <arg name="grounded" value="parent" />
+  <arg name="include_arg" value="dontcare" />
+  <arg name="if_test" value="dontcare" />
+
+  <arg name="param1_name" value="p1" />
+  <arg name="param2_name" value="p2" />
+  <arg name="param3_name" value="p3" />
+
+  <arg name="param1_value" value="$(arg required)" />
+  <arg name="param2_value" value="$(arg optional)" />
+  <arg name="param3_value" value="$(arg grounded)" />
+
+  <param name="$(arg param1_name)_test" value="$(arg param1_value)" />
+  <param name="$(arg param2_name)_test" value="$(arg param2_value)" />
+  <param name="$(arg param3_name)_test" value="$(arg param3_value)" />
+
+  <!-- Normal include: explicitly set args -->
+  <include ns="notall" file="$(find roslaunch)/test/xml/test-arg-include.xml">
+    <arg name="required" value="$(arg required)" />
+    <arg name="include_arg" value="$(arg include_arg)" />
+    <arg name="if_test" value="$(arg if_test)" />
+  </include>
+
+  <!-- Normal include: explicitly set args, including an optional one -->
+  <include ns="notall_optional" file="$(find roslaunch)/test/xml/test-arg-include.xml">
+    <arg name="required" value="$(arg required)" />
+    <arg name="optional" value="$(arg optional)" />
+    <arg name="include_arg" value="$(arg include_arg)" />
+    <arg name="if_test" value="$(arg if_test)" />
+  </include>
+
+  <!-- Include with passing in all args in my namespace -->
+  <include ns="all" file="$(find roslaunch)/test/xml/test-arg-include.xml"
+           pass_all_args="true">
+  </include>
+
+  <!-- Include with passing in all args in my namespace, and then override one
+       of them explicitly -->
+  <include ns="all_override" file="$(find roslaunch)/test/xml/test-arg-include.xml"
+           pass_all_args="true">
+    <arg name="required" value="override" />
+  </include>
+
+</launch>
diff --git a/tools/roslaunch/test/xml/test-arg-invalid-include.xml b/tools/roslaunch/test/xml/test-arg-invalid-include.xml
new file mode 100644
index 0000000..df2a1a7
--- /dev/null
+++ b/tools/roslaunch/test/xml/test-arg-invalid-include.xml
@@ -0,0 +1,5 @@
+<launch>
+  <include file="$(find roslaunch)/test/xml/test-arg-invalid-included.xml">
+    <arg name="grounded" value="not_set"/>
+  </include>
+</launch>
diff --git a/tools/roslaunch/test/xml/test-arg-invalid-include2.xml b/tools/roslaunch/test/xml/test-arg-invalid-include2.xml
new file mode 100644
index 0000000..765fa00
--- /dev/null
+++ b/tools/roslaunch/test/xml/test-arg-invalid-include2.xml
@@ -0,0 +1,6 @@
+<launch>
+  <include file="$(find roslaunch)/test/xml/test-arg-invalid-included.xml" pass_all_args="true">
+    <arg name="grounded" value="not_set"/>
+  </include>
+</launch>
+
diff --git a/tools/roslaunch/test/xml/test-arg-invalid-included.xml b/tools/roslaunch/test/xml/test-arg-invalid-included.xml
new file mode 100644
index 0000000..cee72e0
--- /dev/null
+++ b/tools/roslaunch/test/xml/test-arg-invalid-included.xml
@@ -0,0 +1,3 @@
+<launch>
+  <arg name="grounded" value="set"/>
+</launch>
diff --git a/tools/roslaunch/test/xml/test-arg-valid-include.xml b/tools/roslaunch/test/xml/test-arg-valid-include.xml
new file mode 100644
index 0000000..d330423
--- /dev/null
+++ b/tools/roslaunch/test/xml/test-arg-valid-include.xml
@@ -0,0 +1,5 @@
+<launch>
+  <arg name="grounded" value="not_set"/>
+  <include file="$(find roslaunch)/test/xml/test-arg-invalid-included.xml" pass_all_args="true"/>
+</launch>
+
diff --git a/tools/rosmaster/CHANGELOG.rst b/tools/rosmaster/CHANGELOG.rst
index d5d4e52..2cbd710 100644
--- a/tools/rosmaster/CHANGELOG.rst
+++ b/tools/rosmaster/CHANGELOG.rst
@@ -2,6 +2,15 @@
 Changelog for package rosmaster
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.12.0 (2016-03-18)
+-------------------
+
+1.11.18 (2016-03-17)
+--------------------
+
+1.11.17 (2016-03-11)
+--------------------
+
 1.11.16 (2015-11-09)
 --------------------
 * add `-w` and `-t` options (`#687 <https://github.com/ros/ros_comm/pull/687>`_)
diff --git a/tools/rosmaster/package.xml b/tools/rosmaster/package.xml
index 3723dbf..bbbd9f1 100644
--- a/tools/rosmaster/package.xml
+++ b/tools/rosmaster/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>rosmaster</name>
-  <version>1.11.16</version>
+  <version>1.12.0</version>
   <description>
     ROS <a href="http://ros.org/wiki/Master">Master</a> implementation.
   </description>
diff --git a/tools/rosmaster/src/rosmaster/threadpool.py b/tools/rosmaster/src/rosmaster/threadpool.py
index fa28f6d..8e7cbff 100644
--- a/tools/rosmaster/src/rosmaster/threadpool.py
+++ b/tools/rosmaster/src/rosmaster/threadpool.py
@@ -46,7 +46,7 @@ for gobbling up all of our threads
 import threading, logging, traceback
 from time import sleep
 
-class MarkedThreadPool:
+class MarkedThreadPool(object):
 
     """Flexible thread pool class.  Creates a pool of threads, then
     accepts tasks that will be dispatched to the next available
diff --git a/tools/rosmsg/CHANGELOG.rst b/tools/rosmsg/CHANGELOG.rst
index eaf7b9c..43f6050 100644
--- a/tools/rosmsg/CHANGELOG.rst
+++ b/tools/rosmsg/CHANGELOG.rst
@@ -2,6 +2,16 @@
 Changelog for package rosmsg
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.12.0 (2016-03-18)
+-------------------
+
+1.11.18 (2016-03-17)
+--------------------
+
+1.11.17 (2016-03-11)
+--------------------
+* improve rosmsg show to print error message and return non-zero rc when message is not found (`#691 <https://github.com/ros/ros_comm/issues/691>`_)
+
 1.11.16 (2015-11-09)
 --------------------
 
diff --git a/tools/rosmsg/package.xml b/tools/rosmsg/package.xml
index ab63676..12fdd8b 100644
--- a/tools/rosmsg/package.xml
+++ b/tools/rosmsg/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>rosmsg</name>
-  <version>1.11.16</version>
+  <version>1.12.0</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/rosmsg/src/rosmsg/__init__.py b/tools/rosmsg/src/rosmsg/__init__.py
index 500df33..2d17424 100644
--- a/tools/rosmsg/src/rosmsg/__init__.py
+++ b/tools/rosmsg/src/rosmsg/__init__.py
@@ -610,7 +610,11 @@ def rosmsg_cmd_show(mode, full):
         if '/' in arg: #package specified
             rosmsg_debug(rospack, mode, arg, options.raw)
         else:
-            for found in rosmsg_search(rospack, mode, arg):
+            found_msgs = list(rosmsg_search(rospack, mode, arg))
+            if not found_msgs:
+                print("Could not find msg '%s'" % arg, file=sys.stderr)
+                return 1
+            for found in found_msgs:
                 print("[%s]:"%found)
                 rosmsg_debug(rospack, mode, found, options.raw)
 
@@ -738,7 +742,7 @@ def rosmsgmain(mode=MODE_MSG):
 
         command = sys.argv[1]
         if command == 'show':
-            rosmsg_cmd_show(ext, full)
+            sys.exit(rosmsg_cmd_show(ext, full))
         elif command == 'package':
             rosmsg_cmd_package(ext, full)
         elif command == 'packages':
diff --git a/tools/rosmsg/test/setup.cfg b/tools/rosmsg/test/setup.cfg
deleted file mode 100644
index 0c900d8..0000000
--- a/tools/rosmsg/test/setup.cfg
+++ /dev/null
@@ -1,4 +0,0 @@
-[nosetests]
-with-coverage=1
-cover-package=rosmsg
-with-xunit=1
diff --git a/tools/rosnode/CHANGELOG.rst b/tools/rosnode/CHANGELOG.rst
index 27a9fe6..5c613fe 100644
--- a/tools/rosnode/CHANGELOG.rst
+++ b/tools/rosnode/CHANGELOG.rst
@@ -2,6 +2,15 @@
 Changelog for package rosnode
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.12.0 (2016-03-18)
+-------------------
+
+1.11.18 (2016-03-17)
+--------------------
+
+1.11.17 (2016-03-11)
+--------------------
+
 1.11.16 (2015-11-09)
 --------------------
 
diff --git a/tools/rosnode/package.xml b/tools/rosnode/package.xml
index c6c0750..a3f1cab 100644
--- a/tools/rosnode/package.xml
+++ b/tools/rosnode/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>rosnode</name>
-  <version>1.11.16</version>
+  <version>1.12.0</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/rosnode/test/test_rosnode_command_online.py b/tools/rosnode/test/check_rosnode_command_online.py
similarity index 100%
rename from tools/rosnode/test/test_rosnode_command_online.py
rename to tools/rosnode/test/check_rosnode_command_online.py
diff --git a/tools/rosnode/test/rosnode.test b/tools/rosnode/test/rosnode.test
index 9e87024..5da3921 100644
--- a/tools/rosnode/test/rosnode.test
+++ b/tools/rosnode/test/rosnode.test
@@ -20,5 +20,5 @@
     <node name="kill3" pkg="rospy" type="talker.py" />
     <node name="kill4" pkg="rospy" type="talker.py" />
   </group>
-  <test test-name="rosnode_command_line_online" pkg="rosnode" type="test_rosnode_command_online.py" />
+  <test test-name="rosnode_command_line_online" pkg="rosnode" type="check_rosnode_command_online.py" />
 </launch>
diff --git a/tools/rosnode/test/setup.cfg b/tools/rosnode/test/setup.cfg
deleted file mode 100644
index 2799326..0000000
--- a/tools/rosnode/test/setup.cfg
+++ /dev/null
@@ -1,3 +0,0 @@
-[nosetests]
-with-xunit=1
-tests=test_rosnode_command_offline.py
diff --git a/tools/rosout/CHANGELOG.rst b/tools/rosout/CHANGELOG.rst
index 84ff4cd..3ea36f8 100644
--- a/tools/rosout/CHANGELOG.rst
+++ b/tools/rosout/CHANGELOG.rst
@@ -2,6 +2,15 @@
 Changelog for package rosout
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.12.0 (2016-03-18)
+-------------------
+
+1.11.18 (2016-03-17)
+--------------------
+
+1.11.17 (2016-03-11)
+--------------------
+
 1.11.16 (2015-11-09)
 --------------------
 
diff --git a/tools/rosout/CMakeLists.txt b/tools/rosout/CMakeLists.txt
index 5401956..526cb62 100644
--- a/tools/rosout/CMakeLists.txt
+++ b/tools/rosout/CMakeLists.txt
@@ -1,5 +1,10 @@
 cmake_minimum_required(VERSION 2.8.3)
 project(rosout)
+
+if(NOT WIN32)
+  set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -Wextra")
+endif()
+
 find_package(catkin REQUIRED COMPONENTS roscpp)
 
 catkin_package()
diff --git a/tools/rosout/package.xml b/tools/rosout/package.xml
index 0a93877..b40e309 100644
--- a/tools/rosout/package.xml
+++ b/tools/rosout/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>rosout</name>
-  <version>1.11.16</version>
+  <version>1.12.0</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 8290672..c090b47 100644
--- a/tools/rosparam/CHANGELOG.rst
+++ b/tools/rosparam/CHANGELOG.rst
@@ -2,6 +2,16 @@
 Changelog for package rosparam
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.12.0 (2016-03-18)
+-------------------
+
+1.11.18 (2016-03-17)
+--------------------
+
+1.11.17 (2016-03-11)
+--------------------
+* add support for loading parameters from stdin as well as dumping rosparam to stdout (`#686 <https://github.com/ros/ros_comm/pull/686>`_)
+
 1.11.16 (2015-11-09)
 --------------------
 
diff --git a/tools/rosparam/package.xml b/tools/rosparam/package.xml
index 49a56ca..ac07ed8 100644
--- a/tools/rosparam/package.xml
+++ b/tools/rosparam/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>rosparam</name>
-  <version>1.11.16</version>
+  <version>1.12.0</version>
   <description>
     rosparam contains the rosparam command-line tool for getting and
     setting ROS Parameters on the <a
diff --git a/tools/rosparam/src/rosparam/__init__.py b/tools/rosparam/src/rosparam/__init__.py
index 927789b..7231ac5 100644
--- a/tools/rosparam/src/rosparam/__init__.py
+++ b/tools/rosparam/src/rosparam/__init__.py
@@ -160,15 +160,18 @@ def load_file(filename, default_namespace=None, verbose=False):
       corresponding namespaces for each YAML document in the file
     :raises: :exc:`RosParamException`: if unable to load contents of filename
     """
-    if not os.path.isfile(filename):
-        raise RosParamException("file [%s] does not exist"%filename)
-    if verbose:
-        print("reading parameters from [%s]"%filename)
-    f = open(filename, 'r')
-    try:
+    if not filename or filename == '-':
+        f = sys.stdin
+        if verbose:
+            print("reading parameters from stdin")
         return load_str(f.read(), filename, default_namespace=default_namespace, verbose=verbose)
-    finally:
-        f.close()
+    else:
+        if not os.path.isfile(filename):
+            raise RosParamException("file [%s] does not exist"%filename)
+        if verbose:
+            print("reading parameters from [%s]"%filename)
+        with open(filename, 'r') as f:
+            return load_str(f.read(), filename, default_namespace=default_namespace, verbose=verbose)
         
 def load_str(str, filename, default_namespace=None, verbose=False):
     """
@@ -293,11 +296,15 @@ def dump_params(filename, param, verbose=False):
     tree = get_param(param)
     if verbose:
         print_params(tree, param)
-    f = open(filename, 'w')
-    try:
+    if not filename:
+        f = sys.stdout
         yaml.dump(tree, f)
-    finally:
-        f.close()
+    else:
+        f = open(filename, 'w')
+        try:
+            yaml.dump(tree, f)
+        finally:
+            f.close()
 
 
 def delete_param(param, verbose=False):
@@ -423,9 +430,7 @@ def _rosparam_cmd_get_dump(cmd, argv):
     ns = ''
     
     if len(args) == 0:
-        if cmd == 'dump':
-            parser.error("invalid arguments. Please specify a file name")
-        elif cmd == 'get':
+        if cmd == 'get':
             parser.error("invalid arguments. Please specify a parameter name")
     elif len(args) == 1:
         arg = args[0]
@@ -491,15 +496,17 @@ def _rosparam_cmd_set_load(cmd, argv):
 
     parser.add_option("-v", dest="verbose", default=False,
                       action="store_true", help="turn on verbose output")
-    options, args = _set_optparse_neg_args(parser, argv)
     if cmd == 'set':
+        options, args = _set_optparse_neg_args(parser, argv)
         if options.text_file and options.bin_file:
             parser.error("you may only specify one of --textfile or --binfile")
+    else:
+        options, args = parser.parse_args(argv[2:])
 
     arg2 = None
     if len(args) == 0:
         if cmd == 'load':
-            parser.error("invalid arguments. Please specify a file name")
+            parser.error("invalid arguments. Please specify a file name or - for stdin")
         elif cmd == 'set':
             parser.error("invalid arguments. Please specify a parameter name")
     elif len(args) == 1:
diff --git a/tools/rosservice/CHANGELOG.rst b/tools/rosservice/CHANGELOG.rst
index d5a4b4a..bdfb496 100644
--- a/tools/rosservice/CHANGELOG.rst
+++ b/tools/rosservice/CHANGELOG.rst
@@ -2,6 +2,15 @@
 Changelog for package rosservice
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.12.0 (2016-03-18)
+-------------------
+
+1.11.18 (2016-03-17)
+--------------------
+
+1.11.17 (2016-03-11)
+--------------------
+
 1.11.16 (2015-11-09)
 --------------------
 
diff --git a/tools/rosservice/package.xml b/tools/rosservice/package.xml
index 033651c..e9de2a1 100644
--- a/tools/rosservice/package.xml
+++ b/tools/rosservice/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>rosservice</name>
-  <version>1.11.16</version>
+  <version>1.12.0</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 f5b38b4..36be185 100644
--- a/tools/rostest/CHANGELOG.rst
+++ b/tools/rostest/CHANGELOG.rst
@@ -2,6 +2,19 @@
 Changelog for package rostest
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.12.0 (2016-03-18)
+-------------------
+
+1.11.18 (2016-03-17)
+--------------------
+
+1.11.17 (2016-03-11)
+--------------------
+* rostest.rosrun now generates coverage reports (`#558 <https://github.com/ros/ros_comm/issues/558>`_)
+* rostest can load tests from a dotted name (`#722 <https://github.com/ros/ros_comm/issues/722>`_)
+* include GTEST_INCLUDE_DIRS so that the proper gtest headers are found (`#727 <https://github.com/ros/ros_comm/issues/727>`_)
+* rostest: move replacement of slashes after ARGS handling (`#721 <https://github.com/ros/ros_comm/pull/721>`_)
+
 1.11.16 (2015-11-09)
 --------------------
 
diff --git a/tools/rostest/cmake/rostest-extras.cmake.em b/tools/rostest/cmake/rostest-extras.cmake.em
index 8450d7f..e2562aa 100644
--- a/tools/rostest/cmake/rostest-extras.cmake.em
+++ b/tools/rostest/cmake/rostest-extras.cmake.em
@@ -36,8 +36,6 @@ function(add_rostest file)
   rostest__strip_prefix(_testname "${PROJECT_SOURCE_DIR}/")
   rostest__strip_prefix(_testname "${PROJECT_BINARY_DIR}/")
 
-  string(REPLACE "/" "_" _testname ${_testname})
-
   # to support registering the same test with different ARGS
   # append the args to the test name
   if(_rostest_ARGS)
@@ -50,6 +48,8 @@ function(add_rostest file)
     set(_testname "${_testname}${_ext}")
   endif()
 
+  string(REPLACE "/" "_" _testname ${_testname})
+
   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} --results-base-dir \"${CATKIN_TEST_RESULTS_DIR}\" ${_file_name} ${_rostest_ARGS}")
@@ -76,6 +76,7 @@ function(add_rostest_gtest target launch_file)
     message(FATAL_ERROR "add_rostest_gtest() needs at least one file argument to compile a GTest executable")
   endif()
   if(GTEST_FOUND)
+    include_directories(${GTEST_INCLUDE_DIRS})
     add_executable(${target} EXCLUDE_FROM_ALL ${ARGN})
     target_link_libraries(${target} ${GTEST_LIBRARIES})
     if(TARGET tests)
diff --git a/tools/rostest/package.xml b/tools/rostest/package.xml
index 8e8a48b..f020963 100644
--- a/tools/rostest/package.xml
+++ b/tools/rostest/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>rostest</name>
-  <version>1.11.16</version>
+  <version>1.12.0</version>
   <description>
      Integration test suite based on roslaunch that is compatible with xUnit frameworks.
   </description>
diff --git a/tools/rostest/src/rostest/__init__.py b/tools/rostest/src/rostest/__init__.py
index 5a87cce..5f9e6da 100644
--- a/tools/rostest/src/rostest/__init__.py
+++ b/tools/rostest/src/rostest/__init__.py
@@ -109,8 +109,8 @@ def rosrun(package, test_name, test, sysargs=None):
     @type  package: str
     @param test_name: name of test that is being run
     @type  test_name: str
-    @param test: test class 
-    @type  test: unittest.TestCase
+    @param test: a test case instance or a name resolving to a test case or suite
+    @type  test: unittest.TestCase, or string
     @param sysargs: command-line args. If not specified, this defaults to sys.argv. rostest
       will look for the --text and --gtest_output parameters
     @type  sysargs: list
@@ -128,18 +128,23 @@ def rosrun(package, test_name, test, sysargs=None):
     text_mode = '--text' in sysargs
     coverage_mode = '--cov' in sysargs
     if coverage_mode:
-        _start_coverage(package)
+        _start_coverage([package])
 
     import unittest
     import rospy
     
-    suite = unittest.TestLoader().loadTestsFromTestCase(test)
+    suite = None
+    if issubclass(test, unittest.TestCase):
+        suite = unittest.TestLoader().loadTestsFromTestCase(test)
+    else:
+        suite = unittest.TestLoader().loadTestsFromName(test)
+
     if text_mode:
         result = unittest.TextTestRunner(verbosity=2).run(suite)
     else:
         result = rosunit.create_xml_runner(package, test_name, result_file).run(suite)
     if coverage_mode:
-        _stop_coverage(package)
+        _stop_coverage([package])
     rosunit.print_unittest_summary(result)
     
     # shutdown any node resources in case test forgets to
diff --git a/tools/rostest/test/dotname_cases.py b/tools/rostest/test/dotname_cases.py
new file mode 100755
index 0000000..b7cd25e
--- /dev/null
+++ b/tools/rostest/test/dotname_cases.py
@@ -0,0 +1,36 @@
+import unittest
+
+
+class CaseA(unittest.TestCase):
+
+    def runTest(self):
+        self.assertTrue(True)
+
+
+class CaseB(unittest.TestCase):
+
+    def runTest(self):
+        self.assertTrue(True)
+
+
+class DotnameLoadingSuite(unittest.TestSuite):
+
+    def __init__(self):
+        super(DotnameLoadingSuite, self).__init__()
+        self.addTest(CaseA())
+        self.addTest(CaseB())
+
+
+class DotnameLoadingTest(unittest.TestCase):
+
+    def test_a(self):
+        self.assertTrue(True)
+
+    def test_b(self):
+        self.assertTrue(True)
+
+
+class NotTestCase():
+
+    def not_test(self):
+        pass
diff --git a/tools/rostest/test/test_dotname.py b/tools/rostest/test/test_dotname.py
new file mode 100755
index 0000000..4d6fead
--- /dev/null
+++ b/tools/rostest/test/test_dotname.py
@@ -0,0 +1,52 @@
+#!/usr/bin/env python
+
+# This file should be run using a non-ros unit test framework such as nose using
+# nosetests test_dotname.py.
+
+import unittest
+import rostest
+from dotname_cases import DotnameLoadingTest, NotTestCase, DotnameLoadingSuite
+
+
+class TestDotnameLoading(unittest.TestCase):
+
+    def test_class_basic(self):
+        rostest.rosrun('test_rostest', 'test_class_basic', DotnameLoadingTest)
+
+    def test_class_dotname(self):
+        rostest.rosrun('test_rostest', 'test_class_dotname', 'dotname_cases.DotnameLoadingTest')
+
+    def test_method_dotname(self):
+        rostest.rosrun('test_rostest', 'test_method_dotname', 'dotname_cases.DotnameLoadingTest.test_a')
+
+    def test_suite_dotname(self):
+        rostest.rosrun('test_rostest', 'test_suite_dotname', 'dotname_cases.DotnameLoadingSuite')
+
+    def test_class_basic_nottest(self):
+        # class which exists but is not a TestCase
+        with self.assertRaises(SystemExit):
+            rostest.rosrun('test_rostest', 'test_class_basic_nottest', NotTestCase)
+
+    def test_suite_basic(self):
+        # can't load suites with the basic loader
+        with self.assertRaises(SystemExit):
+            rostest.rosrun('test_rosunit', 'test_suite_basic', DotnameLoadingSuite)
+
+    def test_class_dotname_nottest(self):
+        # class which exists but is not a valid test
+        with self.assertRaises(TypeError):
+            rostest.rosrun('test_rostest', 'test_class_dotname_nottest', 'dotname_cases.NotTestCase')
+
+    def test_class_dotname_noexist(self):
+        # class which does not exist in the module
+        with self.assertRaises(AttributeError):
+            rostest.rosrun('test_rostest', 'test_class_dotname_noexist', 'dotname_cases.DotnameLoading')
+
+    def test_method_dotname_noexist(self):
+        # method which does not exist in the class
+        with self.assertRaises(AttributeError):
+            rostest.rosrun('test_rostest', 'test_method_dotname_noexist', 'dotname_cases.DotnameLoadingTest.not_method')
+
+
+if __name__ == '__main__':
+    unittest.main()
diff --git a/tools/rostopic/CHANGELOG.rst b/tools/rostopic/CHANGELOG.rst
index 0e17ce0..6f90023 100644
--- a/tools/rostopic/CHANGELOG.rst
+++ b/tools/rostopic/CHANGELOG.rst
@@ -2,6 +2,18 @@
 Changelog for package rostopic
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.12.0 (2016-03-18)
+-------------------
+
+1.11.18 (2016-03-17)
+--------------------
+
+1.11.17 (2016-03-11)
+--------------------
+* add "rostopic delay" to measure message delay compared to the input from real world (`#719 <https://github.com/ros/ros_comm/pull/719>`_)
+* add option to perform keyword substitution for messages published with "rostopic pub" (`#702 <https://github.com/ros/ros_comm/pull/702>`_)
+* add wall-time option for rostopic hz (`#674 <https://github.com/ros/ros_comm/pull/674>`_)
+
 1.11.16 (2015-11-09)
 --------------------
 
diff --git a/tools/rostopic/package.xml b/tools/rostopic/package.xml
index c92add2..540245f 100644
--- a/tools/rostopic/package.xml
+++ b/tools/rostopic/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>rostopic</name>
-  <version>1.11.16</version>
+  <version>1.12.0</version>
   <description>
     rostopic contains the rostopic command-line tool for displaying
     debug information about
diff --git a/tools/rostopic/src/rostopic/__init__.py b/tools/rostopic/src/rostopic/__init__.py
index e2b42a4..fe32914 100644
--- a/tools/rostopic/src/rostopic/__init__.py
+++ b/tools/rostopic/src/rostopic/__init__.py
@@ -97,7 +97,7 @@ class ROSTopicHz(object):
     """
     ROSTopicHz receives messages for a topic and computes frequency stats
     """
-    def __init__(self, window_size, filter_expr=None):
+    def __init__(self, window_size, filter_expr=None, use_wtime=False):
         import threading
         self.lock = threading.Lock()
         self.last_printed_tn = 0
@@ -105,6 +105,7 @@ class ROSTopicHz(object):
         self.msg_tn = 0
         self.times =[]
         self.filter_expr = filter_expr
+        self.use_wtime = use_wtime
         
         # can't have infinite window size due to memory restrictions
         if window_size < 0:
@@ -120,7 +121,8 @@ class ROSTopicHz(object):
         if self.filter_expr is not None and not self.filter_expr(m):
             return
         with self.lock:
-            curr_rostime = rospy.get_rostime()
+            curr_rostime = rospy.get_rostime() if not self.use_wtime else \
+                    rospy.Time.from_sec(time.time())
 
             # time reset
             if curr_rostime.is_zero():
@@ -129,7 +131,8 @@ class ROSTopicHz(object):
                     self.times = []
                 return
             
-            curr = curr_rostime.to_sec()
+            curr = curr_rostime.to_sec() if not self.use_wtime else \
+                    rospy.Time.from_sec(time.time()).to_sec()
             if self.msg_t0 < 0 or self.msg_t0 > curr:
                 self.msg_t0 = curr
                 self.msg_tn = curr
@@ -179,7 +182,7 @@ class ROSTopicHz(object):
 def _sleep(duration):
     rospy.rostime.wallsleep(duration)
 
-def _rostopic_hz(topic, window_size=-1, filter_expr=None):
+def _rostopic_hz(topic, window_size=-1, filter_expr=None, use_wtime=False):
     """
     Periodically print the publishing rate of a topic to console until
     shutdown
@@ -191,7 +194,7 @@ def _rostopic_hz(topic, window_size=-1, filter_expr=None):
     if rospy.is_shutdown():
         return
     rospy.init_node(NAME, anonymous=True)
-    rt = ROSTopicHz(window_size, filter_expr=filter_expr)
+    rt = ROSTopicHz(window_size, filter_expr=filter_expr, use_wtime=use_wtime)
     # we use a large buffer size as we don't know what sort of messages we're dealing with.
     # may parameterize this in the future
     if filter_expr is not None:
@@ -207,7 +210,107 @@ def _rostopic_hz(topic, window_size=-1, filter_expr=None):
     while not rospy.is_shutdown():
         _sleep(1.0)
         rt.print_hz()
-    
+
+
+class ROSTopicDelay(object):
+
+    def __init__(self, window_size):
+        import threading
+        self.lock = threading.Lock()
+        self.last_msg_tn = 0
+        self.msg_t0 = -1.
+        self.msg_tn = 0
+        self.delays = []
+
+        # can't have infinite window size due to memory restrictions
+        if window_size < 0:
+            window_size = 50000
+        self.window_size = window_size
+
+    def callback_delay(self, msg):
+        if not msg._has_header:
+            rospy.logerr('msg does not have header')
+            return
+        with self.lock:
+            curr_rostime = rospy.get_rostime()
+
+            # time reset
+            if curr_rostime.is_zero():
+                if len(self.delays) > 0:
+                    print("time has reset, resetting counters")
+                    self.delays = []
+                return
+
+            curr = curr_rostime.to_sec()
+            if self.msg_t0 < 0 or self.msg_t0 > curr:
+                self.msg_t0 = curr
+                self.msg_tn = curr
+                self.delays = []
+            else:
+                self.delays.append(curr_rostime.to_time() -
+                                   msg.header.stamp.to_time())
+                self.msg_tn = curr
+
+            if len(self.delays) > self.window_size - 1:
+                self.delays.pop(0)
+
+    def get_delay(self):
+        if self.msg_tn == self.last_msg_tn:
+            return
+        with self.lock:
+            if not self.delays:
+                return
+            n = len(self.delays)
+
+            mean = sum(self.delays) / n
+            rate = 1. / mean if mean > 0 else 0
+
+            std_dev = math.sqrt(sum((x - mean)**2 for x in self.delays) / n)
+
+            max_delta = max(self.delays)
+            min_delta = min(self.delays)
+
+            self.last_msg_tn = self.msg_tn
+        return mean, min_delta, max_delta, std_dev, n + 1
+
+    def print_delay(self):
+        """
+        print the average publishing delay to screen
+        """
+        if not self.delays:
+            return
+        ret = self.get_delay()
+        if ret is None:
+            print("no new messages")
+            return
+        delay, min_delta, max_delta, std_dev, window = ret
+        print("average delay: %.3f\n\tmin: %.3fs max: %.3fs std dev: %.5fs window: %s"%(delay, min_delta, max_delta, std_dev, window))
+
+
+def _rostopic_delay(topic, window_size=-1):
+    """
+    Periodically print the publishing delay of a topic to console until
+    shutdown
+    :param topic: topic name, ``str``
+    :param window_size: number of messages to average over, -1 for infinite, ``int``
+    """
+    # pause hz until topic is published
+    msg_class, real_topic, _ = get_topic_class(topic, blocking=True)
+    if rospy.is_shutdown():
+        return
+    rospy.init_node(NAME, anonymous=True)
+    rt = ROSTopicDelay(window_size)
+    sub = rospy.Subscriber(real_topic, msg_class, rt.callback_delay)
+    print("subscribed to [%s]" % real_topic)
+
+    if rospy.get_param('use_sim_time', False):
+        print("WARNING: may be using simulated time",file=sys.stderr)
+
+    while not rospy.is_shutdown():
+        _sleep(1.0)
+        rt.print_delay()
+
+
 class ROSTopicBandwidth(object):
     def __init__(self, window_size=100):
         import threading
@@ -1191,6 +1294,9 @@ def _rostopic_cmd_hz(argv):
     parser.add_option("--filter",
                       dest="filter_expr", default=None,
                       help="only measure messages matching the specified Python expression", metavar="EXPR")
+    parser.add_option("--wall-time",
+                      dest="use_wtime", default=False, action="store_true",
+                      help="calculates rate using wall time which can be helpful when clock isnt published during simulation")
 
     (options, args) = parser.parse_args(args)
     if len(args) == 0:
@@ -1216,7 +1322,25 @@ def _rostopic_cmd_hz(argv):
         filter_expr = expr_eval(options.filter_expr)
     else:
         filter_expr = None
-    _rostopic_hz(topic, window_size=window_size, filter_expr=filter_expr)
+    _rostopic_hz(topic, window_size=window_size, filter_expr=filter_expr,
+                 use_wtime=options.use_wtime)
+
+
+def _rostopic_cmd_delay(argv):
+    args = argv[2:]
+    import argparse
+    parser = argparse.ArgumentParser(usage="%(prog)s delay [options] /topic", prog=NAME)
+    parser.add_argument("topic", help="topic name to be calcurated the delay")
+    parser.add_argument("-w", "--window",
+                        dest="window_size", default=-1, type=int,
+                        help="window size, in # of messages, for calculating rate")
+
+    args = parser.parse_args(args)
+    topic_name = args.topic
+    window_size = args.window_size
+    topic = rosgraph.names.script_resolve_name('rostopic', topic_name)
+    _rostopic_delay(topic, window_size=window_size)
+
 
 def _rostopic_cmd_bw(argv=sys.argv):
     args = argv[2:]
@@ -1306,7 +1430,7 @@ def create_publisher(topic_name, topic_type, latch):
     pub = rospy.Publisher(topic_name, msg_class, latch=latch, queue_size=100)
     return pub, msg_class
 
-def _publish_at_rate(pub, msg, rate, verbose=False):
+def _publish_at_rate(pub, msg, rate, verbose=False, substitute_keywords=False, pub_args=None):
     """
     Publish message at specified rate. Subroutine of L{publish_message()}.
     
@@ -1320,6 +1444,8 @@ def _publish_at_rate(pub, msg, rate, verbose=False):
     except ValueError:
         raise ROSTopicException("Rate must be a number")
     while not rospy.is_shutdown():
+        if substitute_keywords:
+            _fillMessageArgs(msg, pub_args)
         if verbose:
             print("publishing %s"%msg)
         pub.publish(msg)
@@ -1343,7 +1469,7 @@ def _publish_latched(pub, msg, once=False, verbose=False):
     if not once:
         rospy.spin()        
 
-def publish_message(pub, msg_class, pub_args, rate=None, once=False, verbose=False):
+def publish_message(pub, msg_class, pub_args, rate=None, once=False, verbose=False, substitute_keywords=False):
     """
     Create new instance of msg_class, populate with pub_args, and publish. This may
     print output to screen.
@@ -1356,24 +1482,9 @@ def publish_message(pub, msg_class, pub_args, rate=None, once=False, verbose=Fal
     :param verbose: If ``True``, print more verbose output to stdout, ``bool``
     """
     msg = msg_class()
-    try:
-        # Populate the message and enable substitution keys for 'now'
-        # and 'auto'. There is a corner case here: this logic doesn't
-        # work if you're publishing a Header only and wish to use
-        # 'auto' with it. This isn't a troubling case, but if we start
-        # allowing more keys in the future, it could become an actual
-        # use case. It greatly complicates logic because we'll have to
-        # do more reasoning over types. to avoid ambiguous cases
-        # (e.g. a std_msgs/String type, which only has a single string
-        # field).
-        
-        # allow the use of the 'now' string with timestamps and 'auto' with header
-        now = rospy.get_rostime() 
-        import std_msgs.msg
-        keys = { 'now': now, 'auto': std_msgs.msg.Header(stamp=now) }
-        genpy.message.fill_message_args(msg, pub_args, keys=keys)
-    except genpy.MessageException as e:
-        raise ROSTopicException(str(e)+"\n\nArgs are: [%s]"%genpy.message.get_printable_message_args(msg))
+
+    _fillMessageArgs(msg, pub_args)
+
     try:
         
         if rate is None:
@@ -1383,17 +1494,36 @@ def publish_message(pub, msg_class, pub_args, rate=None, once=False, verbose=Fal
             else:
                 s = s + ". Press ctrl-C to terminate"
             print(s)
-        
-        if rate is None:
+
             _publish_latched(pub, msg, once, verbose)
         else:
-            _publish_at_rate(pub, msg, rate, verbose)
+            _publish_at_rate(pub, msg, rate, verbose=verbose, substitute_keywords=substitute_keywords, pub_args=pub_args)
             
     except rospy.ROSSerializationException as e:
         import rosmsg
         # we could just print the message definition, but rosmsg is more readable
         raise ROSTopicException("Unable to publish message. One of the fields has an incorrect type:\n"+\
                                 "  %s\n\nmsg file:\n%s"%(e, rosmsg.get_msg_text(msg_class._type)))
+
+def _fillMessageArgs(msg, pub_args):
+    try:
+        # Populate the message and enable substitution keys for 'now'
+        # and 'auto'. There is a corner case here: this logic doesn't
+        # work if you're publishing a Header only and wish to use
+        # 'auto' with it. This isn't a troubling case, but if we start
+        # allowing more keys in the future, it could become an actual
+        # use case. It greatly complicates logic because we'll have to
+        # do more reasoning over types. to avoid ambiguous cases
+        # (e.g. a std_msgs/String type, which only has a single string
+        # field).
+
+        # allow the use of the 'now' string with timestamps and 'auto' with header
+        now = rospy.get_rostime()
+        import std_msgs.msg
+        keys = { 'now': now, 'auto': std_msgs.msg.Header(stamp=now) }
+        genpy.message.fill_message_args(msg, pub_args, keys=keys)
+    except genpy.MessageException as e:
+        raise ROSTopicException(str(e)+"\n\nArgs are: [%s]"%genpy.message.get_printable_message_args(msg))
     
 def _rostopic_cmd_pub(argv):
     """
@@ -1417,6 +1547,8 @@ def _rostopic_cmd_pub(argv):
                       help="read args from YAML file (Bagy)")
     parser.add_option("-l", '--latch', dest="latch", default=False, action="store_true",
                       help="enable latching for -f, -r and piped input.  This latches the first message.")
+    parser.add_option("-s", '--substitute-keywords', dest="substitute_keywords", default=False, action="store_true",
+                      help="When publishing with a rate, performs keyword ('now' or 'auto') substitution for each message")
     #parser.add_option("-p", '--param', dest="parameter", metavar='/PARAM', default=None,
     #                  help="read args from ROS parameter (Bagy format)")
     
@@ -1477,7 +1609,7 @@ def _rostopic_cmd_pub(argv):
             rate = 10.
         stdin_publish(pub, msg_class, rate, options.once, options.file, options.verbose)
     else:
-        argv_publish(pub, msg_class, pub_args, rate, options.once, options.verbose)
+        argv_publish(pub, msg_class, pub_args, rate, options.once, options.verbose, substitute_keywords=options.substitute_keywords)
         
 
 def file_yaml_arg(filename):
@@ -1500,8 +1632,8 @@ def file_yaml_arg(filename):
             raise ROSTopicException("invalid YAML in file: %s"%(str(e)))
     return bagy_iter
     
-def argv_publish(pub, msg_class, pub_args, rate, once, verbose):
-    publish_message(pub, msg_class, pub_args, rate, once, verbose=verbose)
+def argv_publish(pub, msg_class, pub_args, rate, once, verbose, substitute_keywords=False):
+    publish_message(pub, msg_class, pub_args, rate, once, verbose=verbose, substitute_keywords=substitute_keywords)
 
     if once:
         # stick around long enough for others to grab
@@ -1755,6 +1887,7 @@ def _fullusage():
 
 Commands:
 \trostopic bw\tdisplay bandwidth used by topic
+\trostopic delay\tdisplay delay of topic from timestamp in header
 \trostopic echo\tprint messages to screen
 \trostopic find\tfind topics by type
 \trostopic hz\tdisplay publishing rate of topic    
@@ -1795,6 +1928,8 @@ def rostopicmain(argv=None):
             _rostopic_cmd_bw(argv)
         elif command == 'find':
             _rostopic_cmd_find(argv)
+        elif command == 'delay':
+            _rostopic_cmd_delay(argv)
         else:
             _fullusage()
     except socket.error:
diff --git a/tools/rostopic/test/test_rostopic_command_line_online.py b/tools/rostopic/test/check_rostopic_command_line_online.py
similarity index 97%
rename from tools/rostopic/test/test_rostopic_command_line_online.py
rename to tools/rostopic/test/check_rostopic_command_line_online.py
index 7f883ec..51c6d31 100755
--- a/tools/rostopic/test/test_rostopic_command_line_online.py
+++ b/tools/rostopic/test/check_rostopic_command_line_online.py
@@ -117,6 +117,10 @@ class TestRostopicOnline(unittest.TestCase):
                 # hz
                 stdout, stderr = run_for([cmd, 'hz', name], 2.)
                 self.assert_('average rate:' in stdout)
+
+                # delay
+                stdout, stderr = run_for([cmd, 'delay', name], 2.)
+                self.assert_('average rate:' in stdout)
             
         # pub
         #  - pub wait until ctrl-C, so we have to wait then kill it
diff --git a/tools/rostopic/test/rostopic.test b/tools/rostopic/test/rostopic.test
index 0d165fe..0b4f8db 100644
--- a/tools/rostopic/test/rostopic.test
+++ b/tools/rostopic/test/rostopic.test
@@ -6,5 +6,5 @@
   <group ns="bar">
     <node name="talker" pkg="rospy" type="talker.py" />
   </group>
-  <test test-name="rostopic_command_line_online" pkg="rostopic" type="test_rostopic_command_line_online.py" />
+  <test test-name="rostopic_command_line_online" pkg="rostopic" type="check_rostopic_command_line_online.py" />
 </launch>
diff --git a/tools/rostopic/test/setup.cfg b/tools/rostopic/test/setup.cfg
deleted file mode 100644
index a212701..0000000
--- a/tools/rostopic/test/setup.cfg
+++ /dev/null
@@ -1,5 +0,0 @@
-[nosetests]
-with-coverage=1
-cover-package=rostopic
-with-xunit=1
-tests=test/test_rostopic_command_line_offline.py,test_rostopic_unit.py
diff --git a/tools/rostopic/test/test_rostopic.py b/tools/rostopic/test/test_rostopic.py
old mode 100755
new mode 100644
diff --git a/tools/rostopic/test/test_rostopic_command_line_offline.py b/tools/rostopic/test/test_rostopic_command_line_offline.py
index a666e63..5dab1ad 100644
--- a/tools/rostopic/test/test_rostopic_command_line_offline.py
+++ b/tools/rostopic/test/test_rostopic_command_line_offline.py
@@ -47,25 +47,26 @@ class TestRostopicOffline(unittest.TestCase):
     def test_cmd_help(self):
         cmd = 'rostopic'
 
-        sub = ['bw', 'echo', 'hz', 'info', 'list', 'pub', 'type','find']
+        sub = ['bw', 'echo', 'hz', 'delay', 'info', 'list', 'pub', 'type','find']
         output = Popen([cmd], stdout=PIPE).communicate()[0]
         self.assert_('Commands' in output)
         output = Popen([cmd, '-h'], stdout=PIPE).communicate()[0]
         self.assert_('Commands' in output)
         # make sure all the commands are in the usage
         for c in sub:
-            self.assert_("%s %s"%(cmd, c) in output, output)            
+            cmd_sub = "%s %s"%(cmd, c)
+            self.assert_(cmd_sub in output, "'%s' is not in help: \n%s"%(cmd_sub, output))
 
         for c in sub:
             output = Popen([cmd, c, '-h'], stdout=PIPE, stderr=PIPE).communicate()
-            self.assert_("Usage:" in output[0], output)
+            self.assert_("usage:" in output[0].lower(), output)
             # make sure usage refers to the command
             self.assert_("%s %s"%(cmd, c) in output[0], output)
             
         # test no args on commands that require args
-        for c in ['bw', 'echo', 'hz', 'info', 'pub', 'type', 'find']:
+        for c in ['bw', 'echo', 'hz', 'delay', 'info', 'pub', 'type', 'find']:
             output = Popen([cmd, c], stdout=PIPE, stderr=PIPE).communicate()
-            self.assert_("Usage:" in output[0] or "Usage:" in output[1], output)
+            self.assert_("usage:" in output[0].lower() or "usage:" in output[1].lower(), output)
             # make sure usage refers to the command
             self.assert_("%s %s"%(cmd, c) in output[1], output)
             
@@ -85,6 +86,8 @@ class TestRostopicOffline(unittest.TestCase):
         self.assert_(output[1].endswith(msg))
         output = Popen([cmd, 'hz', 'chatter'], **kwds).communicate()
         self.assert_(output[1].endswith(msg))
+        output = Popen([cmd, 'delay', 'chatter'], **kwds).communicate()
+        self.assert_(output[1].endswith(msg))
         output = Popen([cmd, 'list'], **kwds).communicate()
         self.assert_(output[1].endswith(msg))
         output = Popen([cmd, 'pub', 'chatter', 'std_msgs/String', 'hello'], **kwds).communicate()
diff --git a/tools/topic_tools/CHANGELOG.rst b/tools/topic_tools/CHANGELOG.rst
index aee5479..3dc5643 100644
--- a/tools/topic_tools/CHANGELOG.rst
+++ b/tools/topic_tools/CHANGELOG.rst
@@ -2,6 +2,18 @@
 Changelog for package topic_tools
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.12.0 (2016-03-18)
+-------------------
+
+1.11.18 (2016-03-17)
+--------------------
+* fix CMake warning about non-existing targets
+
+1.11.17 (2016-03-11)
+--------------------
+* add --wait-for-start option to relay_field script (`#728 <https://github.com/ros/ros_comm/pull/728>`_)
+* use boost::make_shared instead of new for constructing boost::shared_ptr (`#740 <https://github.com/ros/ros_comm/issues/740>`_)
+
 1.11.16 (2015-11-09)
 --------------------
 
diff --git a/tools/topic_tools/CMakeLists.txt b/tools/topic_tools/CMakeLists.txt
index c9d5605..b76dc63 100644
--- a/tools/topic_tools/CMakeLists.txt
+++ b/tools/topic_tools/CMakeLists.txt
@@ -1,5 +1,10 @@
 cmake_minimum_required(VERSION 2.8.3)
 project(topic_tools)
+
+if(NOT WIN32)
+  set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -Wextra")
+endif()
+
 find_package(catkin COMPONENTS cpp_common message_generation rosconsole roscpp rostime std_msgs xmlrpcpp)
 
 include_directories(include)
@@ -34,11 +39,11 @@ target_link_libraries(switch_mux topic_tools ${catkin_LIBRARIES})
 
 add_executable(mux src/mux.cpp)
 target_link_libraries(mux topic_tools ${catkin_LIBRARIES})
-add_dependencies(topic_tools topic_tools_gencpp)
+add_dependencies(topic_tools ${${PROJECT_NAME}_EXPORTED_TARGETS})
 
 add_executable(demux src/demux.cpp)
 target_link_libraries(demux topic_tools ${catkin_LIBRARIES})
-add_dependencies(topic_tools topic_tools_gencpp)
+add_dependencies(topic_tools ${${PROJECT_NAME}_EXPORTED_TARGETS})
 
 add_executable(relay src/relay.cpp)
 target_link_libraries(relay topic_tools ${catkin_LIBRARIES})
diff --git a/tools/topic_tools/include/topic_tools/shape_shifter.h b/tools/topic_tools/include/topic_tools/shape_shifter.h
index a9cdd19..be9ab95 100644
--- a/tools/topic_tools/include/topic_tools/shape_shifter.h
+++ b/tools/topic_tools/include/topic_tools/shape_shifter.h
@@ -205,7 +205,7 @@ boost::shared_ptr<M> ShapeShifter::instantiate() const
   if (ros::message_traits::md5sum<M>() != getMD5Sum())
     throw ShapeShifterException("Tried to instantiate message without matching md5sum.");
   
-  boost::shared_ptr<M> p(new M());
+  boost::shared_ptr<M> p(boost::make_shared<M>());
 
   ros::serialization::IStream s(msgBuf, msgBufUsed);
   ros::serialization::deserialize(s, *p);
diff --git a/tools/topic_tools/package.xml b/tools/topic_tools/package.xml
index b8ce54f..90cb33d 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.16</version>
+  <version>1.12.0</version>
   <description>
     Tools for directing, throttling, selecting, and otherwise messing with
     ROS topics at a meta level. None of the programs in this package actually
diff --git a/tools/topic_tools/scripts/relay_field b/tools/topic_tools/scripts/relay_field
index 17eebbf..6630b68 100755
--- a/tools/topic_tools/scripts/relay_field
+++ b/tools/topic_tools/scripts/relay_field
@@ -70,13 +70,19 @@ class RelayField(object):
             'expression',
             help='Python expression to apply on the input message \'m\'.'
             )
+        parser.add_argument(
+            '--wait-for-start', action='store_true',
+            help='Wait for input messages.'
+            )
 
-        args = parser.parse_args()
+        # get and strip out ros args first                                                                                                                      
+        argv = rospy.myargv()
+        args = parser.parse_args(argv[1:])
 
         self.expression = args.expression
 
         input_class, input_topic, self.input_fn = rostopic.get_topic_class(
-            args.input)
+            args.input, blocking=args.wait_for_start)
         if input_topic is None:
             print('ERROR: Wrong input topic (or topic field): %s' % args.input,
                   file=sys.stderr)
diff --git a/tools/topic_tools/src/demux.cpp b/tools/topic_tools/src/demux.cpp
index a20e409..3740af1 100644
--- a/tools/topic_tools/src/demux.cpp
+++ b/tools/topic_tools/src/demux.cpp
@@ -153,6 +153,7 @@ void in_cb(const boost::shared_ptr<ShapeShifter const>& msg)
 bool list_topic_cb(topic_tools::DemuxList::Request& req,
 	 	   topic_tools::DemuxList::Response& res)
 {
+  (void)req;
   for (list<struct pub_info_t>::iterator it = g_pubs.begin();
        it != g_pubs.end();
        ++it)
@@ -166,6 +167,7 @@ bool list_topic_cb(topic_tools::DemuxList::Request& req,
 bool add_topic_cb(topic_tools::DemuxAdd::Request& req,
 		  topic_tools::DemuxAdd::Response& res)
 {
+  (void)res;
   // Check that it's not already in our list
   ROS_INFO("trying to add %s to demux", req.topic.c_str());
 
@@ -203,6 +205,7 @@ bool add_topic_cb(topic_tools::DemuxAdd::Request& req,
 bool del_topic_cb(topic_tools::DemuxDelete::Request& req,
 		  topic_tools::DemuxDelete::Response& res)
 {
+  (void)res;
   // Check that it's in our list
   ROS_INFO("trying to delete %s from demux", req.topic.c_str());
   // spin through our vector of inputs and find this guy
diff --git a/tools/topic_tools/src/mux.cpp b/tools/topic_tools/src/mux.cpp
index 703af00..f6b0b43 100644
--- a/tools/topic_tools/src/mux.cpp
+++ b/tools/topic_tools/src/mux.cpp
@@ -184,6 +184,7 @@ void in_cb(const boost::shared_ptr<ShapeShifter const>& msg,
 bool list_topic_cb(topic_tools::MuxList::Request& req,
 	 	   topic_tools::MuxList::Response& res)
 {
+  (void)req;
   for (list<struct sub_info_t>::iterator it = g_subs.begin();
        it != g_subs.end();
        ++it)
@@ -197,6 +198,7 @@ bool list_topic_cb(topic_tools::MuxList::Request& req,
 bool add_topic_cb(topic_tools::MuxAdd::Request& req,
 		  topic_tools::MuxAdd::Response& res)
 {
+  (void)res;
   // Check that it's not already in our list
   ROS_INFO("trying to add %s to mux", req.topic.c_str());
   
@@ -248,6 +250,7 @@ bool add_topic_cb(topic_tools::MuxAdd::Request& req,
 bool del_topic_cb(topic_tools::MuxDelete::Request& req,
 		  topic_tools::MuxDelete::Response& res)
 {
+  (void)res;
   // Check that it's in our list
   ROS_INFO("trying to delete %s from mux", req.topic.c_str());
   // spin through our vector of inputs and find this guy
diff --git a/utilities/message_filters/CHANGELOG.rst b/utilities/message_filters/CHANGELOG.rst
index 954af89..bbe9934 100644
--- a/utilities/message_filters/CHANGELOG.rst
+++ b/utilities/message_filters/CHANGELOG.rst
@@ -2,6 +2,18 @@
 Changelog for package message_filters
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.12.0 (2016-03-18)
+-------------------
+
+1.11.18 (2016-03-17)
+--------------------
+* fix compiler warnings
+
+1.11.17 (2016-03-11)
+--------------------
+* use boost::make_shared instead of new for constructing boost::shared_ptr (`#740 <https://github.com/ros/ros_comm/issues/740>`_)
+* add __getattr_\_ to handle sub in message_filters as standard one (`#700 <https://github.com/ros/ros_comm/pull/700>`_)
+
 1.11.16 (2015-11-09)
 --------------------
 
diff --git a/utilities/message_filters/CMakeLists.txt b/utilities/message_filters/CMakeLists.txt
index c095f0c..67cb359 100644
--- a/utilities/message_filters/CMakeLists.txt
+++ b/utilities/message_filters/CMakeLists.txt
@@ -1,5 +1,10 @@
 cmake_minimum_required(VERSION 2.8.3)
 project(message_filters)
+
+if(NOT WIN32)
+  set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -Wextra")
+endif()
+
 find_package(catkin REQUIRED COMPONENTS roscpp xmlrpcpp rosconsole)
 catkin_package(
   INCLUDE_DIRS include
diff --git a/utilities/message_filters/conf.py b/utilities/message_filters/conf.py
index d5cb76f..7dbb529 100644
--- a/utilities/message_filters/conf.py
+++ b/utilities/message_filters/conf.py
@@ -63,6 +63,8 @@ release = '0.1.0'
 # List of documents that shouldn't be included in the build.
 #unused_docs = []
 
+exclude_patterns = ['CHANGELOG.rst']
+
 # List of directories, relative to source directory, that shouldn't be searched
 # for source files.
 exclude_trees = ['_build']
@@ -121,7 +123,7 @@ html_theme = 'default'
 # Add any paths that contain custom static files (such as style sheets) here,
 # relative to this directory. They are copied after the builtin static files,
 # so a file named "default.css" will overwrite the builtin "default.css".
-html_static_path = ['_static']
+html_static_path = []
 
 # If not '', a 'Last updated on:' timestamp is inserted at every page bottom,
 # using the given strftime format.
diff --git a/utilities/message_filters/include/message_filters/chain.h b/utilities/message_filters/include/message_filters/chain.h
index 376e856..a3bfd5c 100644
--- a/utilities/message_filters/include/message_filters/chain.h
+++ b/utilities/message_filters/include/message_filters/chain.h
@@ -92,8 +92,8 @@ void myCallback(const MsgConstPtr& msg)
 }
 
 Chain<Msg> c;
-c.addFilter(boost::shared_ptr<PassThrough<Msg> >(new PassThrough<Msg>));
-c.addFilter(boost::shared_ptr<PassThrough<Msg> >(new PassThrough<Msg>));
+c.addFilter(boost::make_shared<PassThrough<Msg> >());
+c.addFilter(boost::make_shared<PassThrough<Msg> >());
 c.registerCallback(myCallback);
 \endverbatim
 
@@ -156,7 +156,7 @@ public:
     FilterInfo info;
     info.add_func = boost::bind((void(F::*)(const EventType&))&F::add, filter.get(), _1);
     info.filter = filter;
-    info.passthrough.reset(new PassThrough<M>);
+    info.passthrough = boost::make_shared<PassThrough<M> >();
 
     last_filter_connection_.disconnect();
     info.passthrough->connectInput(*filter);
diff --git a/utilities/message_filters/include/message_filters/null_types.h b/utilities/message_filters/include/message_filters/null_types.h
index ef429d0..3e8cd48 100644
--- a/utilities/message_filters/include/message_filters/null_types.h
+++ b/utilities/message_filters/include/message_filters/null_types.h
@@ -54,13 +54,13 @@ template<class M>
 struct NullFilter
 {
   template<typename C>
-  Connection registerCallback(const C& callback)
+  Connection registerCallback(const C&)
   {
     return Connection();
   }
 
   template<typename P>
-  Connection registerCallback(const boost::function<void(P)>& callback)
+  Connection registerCallback(const boost::function<void(P)>&)
   {
     return Connection();
   }
diff --git a/utilities/message_filters/include/message_filters/subscriber.h b/utilities/message_filters/include/message_filters/subscriber.h
index 9015514..b69a3da 100644
--- a/utilities/message_filters/include/message_filters/subscriber.h
+++ b/utilities/message_filters/include/message_filters/subscriber.h
@@ -188,6 +188,7 @@ public:
   template<typename F>
   void connectInput(F& f)
   {
+    (void)f;
   }
 
   /**
@@ -195,6 +196,7 @@ public:
    */
   void add(const EventType& e)
   {
+    (void)e;
   }
 
 private:
diff --git a/utilities/message_filters/package.xml b/utilities/message_filters/package.xml
index 714587e..f734151 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.16</version>
+  <version>1.12.0</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 ae6b929..9cc21c4 100644
--- a/utilities/message_filters/src/message_filters/__init__.py
+++ b/utilities/message_filters/src/message_filters/__init__.py
@@ -34,7 +34,7 @@ import itertools
 import threading
 import rospy
 
-class SimpleFilter:
+class SimpleFilter(object):
 
     def __init__(self):
         self.callbacks = {}
@@ -76,8 +76,9 @@ class Subscriber(SimpleFilter):
     def getTopic(self):
         return self.topic
 
-    def unregister(self):
-        self.sub.unregister()
+    def __getattr__(self, key):
+        """Serve same API as rospy.Subscriber"""
+        return self.sub.__getattribute__(key)
 
 class Cache(SimpleFilter):
 
diff --git a/utilities/message_filters/test/msg_cache_unittest.cpp b/utilities/message_filters/test/msg_cache_unittest.cpp
index 809c3d2..20fc47f 100644
--- a/utilities/message_filters/test/msg_cache_unittest.cpp
+++ b/utilities/message_filters/test/msg_cache_unittest.cpp
@@ -209,7 +209,7 @@ TEST(Cache, eventInEventOut)
   EventHelper h;
   c1.registerCallback(&EventHelper::cb, &h);
 
-  ros::MessageEvent<Msg const> evt(MsgConstPtr(new Msg), ros::Time(4));
+  ros::MessageEvent<Msg const> evt(boost::make_shared<Msg const>(), ros::Time(4));
   c0.add(evt);
 
   EXPECT_EQ(h.event_.getReceiptTime(), evt.getReceiptTime());
diff --git a/utilities/message_filters/test/test_approximate_time_policy.cpp b/utilities/message_filters/test/test_approximate_time_policy.cpp
index b8ea54f..211e6d5 100644
--- a/utilities/message_filters/test/test_approximate_time_policy.cpp
+++ b/utilities/message_filters/test/test_approximate_time_policy.cpp
@@ -120,13 +120,13 @@ public:
     {
       if (input_[i].second == 0)
       {
-        MsgPtr p(new Msg);
+        MsgPtr p(boost::make_shared<Msg>());
         p->header.stamp = input_[i].first;
         sync_.add<0>(p);
       }
       else
       {
-        MsgPtr q(new Msg);
+        MsgPtr q(boost::make_shared<Msg>());
         q->header.stamp = input_[i].first;
         sync_.add<1>(q);
       }
@@ -180,7 +180,7 @@ public:
   {
     for (unsigned int i = 0; i < input_.size(); i++)
     {
-      MsgPtr p(new Msg);
+      MsgPtr p(boost::make_shared<Msg>());
       p->header.stamp = input_[i].first;
       switch (input_[i].second)
       {
diff --git a/utilities/message_filters/test/test_chain.cpp b/utilities/message_filters/test/test_chain.cpp
index 6694c8f..8785add 100644
--- a/utilities/message_filters/test/test_chain.cpp
+++ b/utilities/message_filters/test/test_chain.cpp
@@ -67,12 +67,12 @@ TEST(Chain, simple)
 {
   Helper h;
   Chain<Msg> c;
-  c.addFilter(PassThroughPtr(new PassThrough<Msg>));
+  c.addFilter(boost::make_shared<PassThrough<Msg> >());
   c.registerCallback(boost::bind(&Helper::cb, &h));
 
-  c.add(MsgPtr(new Msg));
+  c.add(boost::make_shared<Msg>());
   EXPECT_EQ(h.count_, 1);
-  c.add(MsgPtr(new Msg));
+  c.add(boost::make_shared<Msg>());
   EXPECT_EQ(h.count_, 2);
 }
 
@@ -80,15 +80,15 @@ TEST(Chain, multipleFilters)
 {
   Helper h;
   Chain<Msg> c;
-  c.addFilter(PassThroughPtr(new PassThrough<Msg>));
-  c.addFilter(PassThroughPtr(new PassThrough<Msg>));
-  c.addFilter(PassThroughPtr(new PassThrough<Msg>));
-  c.addFilter(PassThroughPtr(new PassThrough<Msg>));
+  c.addFilter(boost::make_shared<PassThrough<Msg> >());
+  c.addFilter(boost::make_shared<PassThrough<Msg> >());
+  c.addFilter(boost::make_shared<PassThrough<Msg> >());
+  c.addFilter(boost::make_shared<PassThrough<Msg> >());
   c.registerCallback(boost::bind(&Helper::cb, &h));
 
-  c.add(MsgPtr(new Msg));
+  c.add(boost::make_shared<Msg>());
   EXPECT_EQ(h.count_, 1);
-  c.add(MsgPtr(new Msg));
+  c.add(boost::make_shared<Msg>());
   EXPECT_EQ(h.count_, 2);
 }
 
@@ -96,17 +96,17 @@ TEST(Chain, addingFilters)
 {
   Helper h;
   Chain<Msg> c;
-  c.addFilter(PassThroughPtr(new PassThrough<Msg>));
-  c.addFilter(PassThroughPtr(new PassThrough<Msg>));
+  c.addFilter(boost::make_shared<PassThrough<Msg> >());
+  c.addFilter(boost::make_shared<PassThrough<Msg> >());
   c.registerCallback(boost::bind(&Helper::cb, &h));
 
-  c.add(MsgPtr(new Msg));
+  c.add(boost::make_shared<Msg>());
   EXPECT_EQ(h.count_, 1);
 
-  c.addFilter(PassThroughPtr(new PassThrough<Msg>));
-  c.addFilter(PassThroughPtr(new PassThrough<Msg>));
+  c.addFilter(boost::make_shared<PassThrough<Msg> >());
+  c.addFilter(boost::make_shared<PassThrough<Msg> >());
 
-  c.add(MsgPtr(new Msg));
+  c.add(boost::make_shared<Msg>());
   EXPECT_EQ(h.count_, 2);
 }
 
@@ -114,15 +114,15 @@ TEST(Chain, inputFilter)
 {
   Helper h;
   Chain<Msg> c;
-  c.addFilter(PassThroughPtr(new PassThrough<Msg>));
+  c.addFilter(boost::make_shared<PassThrough<Msg> >());
   c.registerCallback(boost::bind(&Helper::cb, &h));
 
   PassThrough<Msg> p;
   c.connectInput(p);
-  p.add(MsgPtr(new Msg));
+  p.add(boost::make_shared<Msg>());
   EXPECT_EQ(h.count_, 1);
 
-  p.add(MsgPtr(new Msg));
+  p.add(boost::make_shared<Msg>());
   EXPECT_EQ(h.count_, 2);
 }
 
@@ -134,9 +134,9 @@ TEST(Chain, nonSharedPtrFilter)
   c.addFilter(&p);
   c.registerCallback(boost::bind(&Helper::cb, &h));
 
-  c.add(MsgPtr(new Msg));
+  c.add(boost::make_shared<Msg>());
   EXPECT_EQ(h.count_, 1);
-  c.add(MsgPtr(new Msg));
+  c.add(boost::make_shared<Msg>());
   EXPECT_EQ(h.count_, 2);
 }
 
@@ -146,7 +146,7 @@ TEST(Chain, retrieveFilter)
 
   ASSERT_FALSE(c.getFilter<PassThrough<Msg> >(0));
 
-  c.addFilter(PassThroughPtr(new PassThrough<Msg>));
+  c.addFilter(boost::make_shared<PassThrough<Msg> >());
 
   ASSERT_TRUE(c.getFilter<PassThrough<Msg> >(0));
   ASSERT_FALSE(c.getFilter<PassThrough<Msg> >(1));
@@ -159,7 +159,7 @@ TEST(Chain, retrieveFilterThroughBaseClass)
 
   ASSERT_FALSE(cb->getFilter<PassThrough<Msg> >(0));
 
-  c.addFilter(PassThroughPtr(new PassThrough<Msg>));
+  c.addFilter(boost::make_shared<PassThrough<Msg> >());
 
   ASSERT_TRUE(cb->getFilter<PassThrough<Msg> >(0));
   ASSERT_FALSE(cb->getFilter<PassThrough<Msg> >(1));
@@ -173,7 +173,7 @@ struct PTDerived : public PassThrough<Msg>
 TEST(Chain, retrieveBaseClass)
 {
   Chain<Msg> c;
-  c.addFilter(PassThroughPtr(new PTDerived));
+  c.addFilter(boost::make_shared<PTDerived>());
   ASSERT_TRUE(c.getFilter<PassThrough<Msg> >(0));
   ASSERT_TRUE(c.getFilter<PTDerived>(0));
 }
diff --git a/utilities/message_filters/test/test_exact_time_policy.cpp b/utilities/message_filters/test/test_exact_time_policy.cpp
index 3639413..cb9a785 100644
--- a/utilities/message_filters/test/test_exact_time_policy.cpp
+++ b/utilities/message_filters/test/test_exact_time_policy.cpp
@@ -106,13 +106,13 @@ TEST(ExactTime, multipleTimes)
   Sync3 sync(2);
   Helper h;
   sync.registerCallback(boost::bind(&Helper::cb, &h));
-  MsgPtr m(new Msg);
+  MsgPtr m(boost::make_shared<Msg>());
   m->header.stamp = ros::Time();
 
   sync.add<0>(m);
   ASSERT_EQ(h.count_, 0);
 
-  m.reset(new Msg);
+  m = boost::make_shared<Msg>();
   m->header.stamp = ros::Time(0.1);
   sync.add<1>(m);
   ASSERT_EQ(h.count_, 0);
@@ -127,7 +127,7 @@ TEST(ExactTime, queueSize)
   Sync3 sync(1);
   Helper h;
   sync.registerCallback(boost::bind(&Helper::cb, &h));
-  MsgPtr m(new Msg);
+  MsgPtr m(boost::make_shared<Msg>());
   m->header.stamp = ros::Time();
 
   sync.add<0>(m);
@@ -135,12 +135,12 @@ TEST(ExactTime, queueSize)
   sync.add<1>(m);
   ASSERT_EQ(h.count_, 0);
 
-  m.reset(new Msg);
+  m = boost::make_shared<Msg>();
   m->header.stamp = ros::Time(0.1);
   sync.add<1>(m);
   ASSERT_EQ(h.count_, 0);
 
-  m.reset(new Msg);
+  m = boost::make_shared<Msg>();
   m->header.stamp = ros::Time(0);
   sync.add<1>(m);
   ASSERT_EQ(h.count_, 0);
@@ -154,7 +154,7 @@ TEST(ExactTime, dropCallback)
   Helper h;
   sync.registerCallback(boost::bind(&Helper::cb, &h));
   sync.getPolicy()->registerDropCallback(boost::bind(&Helper::dropcb, &h));
-  MsgPtr m(new Msg);
+  MsgPtr m(boost::make_shared<Msg>());
   m->header.stamp = ros::Time();
 
   sync.add<0>(m);
@@ -182,7 +182,7 @@ TEST(ExactTime, eventInEventOut)
   Sync2 sync(2);
   EventHelper h;
   sync.registerCallback(&EventHelper::callback, &h);
-  ros::MessageEvent<Msg const> evt(MsgPtr(new Msg), ros::Time(4));
+  ros::MessageEvent<Msg const> evt(boost::make_shared<Msg>(), ros::Time(4));
 
   sync.add<0>(evt);
   sync.add<1>(evt);
diff --git a/utilities/message_filters/test/test_simple.cpp b/utilities/message_filters/test/test_simple.cpp
index 9ebc18c..bb844da 100644
--- a/utilities/message_filters/test/test_simple.cpp
+++ b/utilities/message_filters/test/test_simple.cpp
@@ -64,42 +64,42 @@ public:
     counts_.assign(0);
   }
 
-  void cb0(const MsgConstPtr& msg)
+  void cb0(const MsgConstPtr&)
   {
     ++counts_[0];
   }
 
-  void cb1(const Msg& msg)
+  void cb1(const Msg&)
   {
     ++counts_[1];
   }
 
-  void cb2(MsgConstPtr msg)
+  void cb2(MsgConstPtr)
   {
     ++counts_[2];
   }
 
-  void cb3(const ros::MessageEvent<Msg const>& evt)
+  void cb3(const ros::MessageEvent<Msg const>&)
   {
     ++counts_[3];
   }
 
-  void cb4(Msg msg)
+  void cb4(Msg)
   {
     ++counts_[4];
   }
 
-  void cb5(const MsgPtr& msg)
+  void cb5(const MsgPtr&)
   {
     ++counts_[5];
   }
 
-  void cb6(MsgPtr msg)
+  void cb6(MsgPtr)
   {
     ++counts_[6];
   }
 
-  void cb7(const ros::MessageEvent<Msg>& evt)
+  void cb7(const ros::MessageEvent<Msg>&)
   {
     ++counts_[7];
   }
@@ -120,7 +120,7 @@ TEST(SimpleFilter, callbackTypes)
   f.registerCallback<MsgPtr>(boost::bind(&Helper::cb6, &h, _1));
   f.registerCallback<const ros::MessageEvent<Msg>&>(boost::bind(&Helper::cb7, &h, _1));
 
-  f.add(Filter::EventType(MsgPtr(new Msg)));
+  f.add(Filter::EventType(boost::make_shared<Msg>()));
   EXPECT_EQ(h.counts_[0], 1);
   EXPECT_EQ(h.counts_[1], 1);
   EXPECT_EQ(h.counts_[2], 1);
@@ -133,7 +133,7 @@ TEST(SimpleFilter, callbackTypes)
 
 struct OldFilter
 {
-  Connection registerCallback(const boost::function<void(const MsgConstPtr&)>& func)
+  Connection registerCallback(const boost::function<void(const MsgConstPtr&)>&)
   {
     return Connection();
   }
diff --git a/utilities/message_filters/test/test_subscriber.cpp b/utilities/message_filters/test/test_subscriber.cpp
index c59bc0b..a3fdffa 100644
--- a/utilities/message_filters/test/test_subscriber.cpp
+++ b/utilities/message_filters/test/test_subscriber.cpp
@@ -105,7 +105,7 @@ TEST(Subscriber, subInChain)
   ros::NodeHandle nh;
   Helper h;
   Chain<Msg> c;
-  c.addFilter(boost::shared_ptr<Subscriber<Msg> >(new Subscriber<Msg>(nh, "test_topic", 0)));
+  c.addFilter(boost::make_shared<Subscriber<Msg> >(boost::ref(nh), "test_topic", 0));
   c.registerCallback(boost::bind(&Helper::cb, &h, _1));
   ros::Publisher pub = nh.advertise<Msg>("test_topic", 0);
 
@@ -147,7 +147,7 @@ TEST(Subscriber, singleNonConstCallback)
   Subscriber<Msg> sub(nh, "test_topic", 0);
   sub.registerCallback(&NonConstHelper::cb, &h);
   ros::Publisher pub = nh.advertise<Msg>("test_topic", 0);
-  MsgPtr msg(new Msg);
+  MsgPtr msg(boost::make_shared<Msg>());
   pub.publish(msg);
 
   ros::spinOnce();
@@ -164,7 +164,7 @@ TEST(Subscriber, multipleNonConstCallbacksFilterSubscriber)
   sub.registerCallback(&NonConstHelper::cb, &h);
   sub.registerCallback(&NonConstHelper::cb, &h2);
   ros::Publisher pub = nh.advertise<Msg>("test_topic", 0);
-  MsgPtr msg(new Msg);
+  MsgPtr msg(boost::make_shared<Msg>());
   pub.publish(msg);
 
   ros::spinOnce();
@@ -184,7 +184,7 @@ TEST(Subscriber, multipleCallbacksSomeFilterSomeDirect)
   sub.registerCallback(&NonConstHelper::cb, &h);
   ros::Subscriber sub2 = nh.subscribe("test_topic", 0, &NonConstHelper::cb, &h2);
   ros::Publisher pub = nh.advertise<Msg>("test_topic", 0);
-  MsgPtr msg(new Msg);
+  MsgPtr msg(boost::make_shared<Msg>());
   pub.publish(msg);
 
   ros::spinOnce();
diff --git a/utilities/message_filters/test/test_synchronizer.cpp b/utilities/message_filters/test/test_synchronizer.cpp
index 3afac04..8e0fc90 100644
--- a/utilities/message_filters/test/test_synchronizer.cpp
+++ b/utilities/message_filters/test/test_synchronizer.cpp
@@ -75,12 +75,12 @@ struct NullPolicy : public PolicyBase<M0, M1, M2, M3, M4, M5, M6, M7, M8>
     }
   }
 
-  void initParent(Sync* parent)
+  void initParent(Sync*)
   {
   }
 
   template<int i>
-  void add(const typename mpl::at_c<Events, i>::type& evt)
+  void add(const typename mpl::at_c<Events, i>::type&)
   {
     ++added_.at(i);
   }
@@ -265,7 +265,7 @@ TEST(Synchronizer, compileMethod8)
 TEST(Synchronizer, add2)
 {
   Synchronizer<Policy2> sync;
-  MsgPtr m(new Msg);
+  MsgPtr m(boost::make_shared<Msg>());
 
   ASSERT_EQ(sync.added_[0], 0);
   sync.add<0>(m);
@@ -278,7 +278,7 @@ TEST(Synchronizer, add2)
 TEST(Synchronizer, add3)
 {
   Synchronizer<Policy3> sync;
-  MsgPtr m(new Msg);
+  MsgPtr m(boost::make_shared<Msg>());
 
   ASSERT_EQ(sync.added_[0], 0);
   sync.add<0>(m);
@@ -294,7 +294,7 @@ TEST(Synchronizer, add3)
 TEST(Synchronizer, add4)
 {
   Synchronizer<Policy4> sync;
-  MsgPtr m(new Msg);
+  MsgPtr m(boost::make_shared<Msg>());
 
   ASSERT_EQ(sync.added_[0], 0);
   sync.add<0>(m);
@@ -313,7 +313,7 @@ TEST(Synchronizer, add4)
 TEST(Synchronizer, add5)
 {
   Synchronizer<Policy5> sync;
-  MsgPtr m(new Msg);
+  MsgPtr m(boost::make_shared<Msg>());
 
   ASSERT_EQ(sync.added_[0], 0);
   sync.add<0>(m);
@@ -335,7 +335,7 @@ TEST(Synchronizer, add5)
 TEST(Synchronizer, add6)
 {
   Synchronizer<Policy6> sync;
-  MsgPtr m(new Msg);
+  MsgPtr m(boost::make_shared<Msg>());
 
   ASSERT_EQ(sync.added_[0], 0);
   sync.add<0>(m);
@@ -360,7 +360,7 @@ TEST(Synchronizer, add6)
 TEST(Synchronizer, add7)
 {
   Synchronizer<Policy7> sync;
-  MsgPtr m(new Msg);
+  MsgPtr m(boost::make_shared<Msg>());
 
   ASSERT_EQ(sync.added_[0], 0);
   sync.add<0>(m);
@@ -388,7 +388,7 @@ TEST(Synchronizer, add7)
 TEST(Synchronizer, add8)
 {
   Synchronizer<Policy8> sync;
-  MsgPtr m(new Msg);
+  MsgPtr m(boost::make_shared<Msg>());
 
   ASSERT_EQ(sync.added_[0], 0);
   sync.add<0>(m);
@@ -419,7 +419,7 @@ TEST(Synchronizer, add8)
 TEST(Synchronizer, add9)
 {
   Synchronizer<Policy9> sync;
-  MsgPtr m(new Msg);
+  MsgPtr m(boost::make_shared<Msg>());
 
   ASSERT_EQ(sync.added_[0], 0);
   sync.add<0>(m);
diff --git a/utilities/message_filters/test/time_sequencer_unittest.cpp b/utilities/message_filters/test/time_sequencer_unittest.cpp
index d852ce3..b804ad9 100644
--- a/utilities/message_filters/test/time_sequencer_unittest.cpp
+++ b/utilities/message_filters/test/time_sequencer_unittest.cpp
@@ -88,7 +88,7 @@ TEST(TimeSequencer, simple)
   TimeSequencer<Msg> seq(ros::Duration(1.0), ros::Duration(0.01), 10);
   Helper h;
   seq.registerCallback(boost::bind(&Helper::cb, &h, _1));
-  MsgPtr msg(new Msg);
+  MsgPtr msg(boost::make_shared<Msg>());
   msg->header.stamp = ros::Time::now();
   seq.add(msg);
 
@@ -129,7 +129,7 @@ TEST(TimeSequencer, eventInEventOut)
   EventHelper h;
   seq2.registerCallback(&EventHelper::cb, &h);
 
-  ros::MessageEvent<Msg const> evt(MsgConstPtr(new Msg), ros::Time::now());
+  ros::MessageEvent<Msg const> evt(boost::make_shared<Msg const>(), ros::Time::now());
   seq.add(evt);
 
   ros::Time::setNow(ros::Time::now() + ros::Duration(2));
diff --git a/utilities/message_filters/test/time_synchronizer_unittest.cpp b/utilities/message_filters/test/time_synchronizer_unittest.cpp
index 8213965..09ce5e6 100644
--- a/utilities/message_filters/test/time_synchronizer_unittest.cpp
+++ b/utilities/message_filters/test/time_synchronizer_unittest.cpp
@@ -263,7 +263,7 @@ TEST(TimeSynchronizer, immediate2)
   TimeSynchronizer<Msg, Msg> sync(1);
   Helper h;
   sync.registerCallback(boost::bind(&Helper::cb, &h));
-  MsgPtr m(new Msg);
+  MsgPtr m(boost::make_shared<Msg>());
   m->header.stamp = ros::Time::now();
 
   sync.add0(m);
@@ -277,7 +277,7 @@ TEST(TimeSynchronizer, immediate3)
   TimeSynchronizer<Msg, Msg, Msg> sync(1);
   Helper h;
   sync.registerCallback(boost::bind(&Helper::cb, &h));
-  MsgPtr m(new Msg);
+  MsgPtr m(boost::make_shared<Msg>());
   m->header.stamp = ros::Time::now();
 
   sync.add0(m);
@@ -293,7 +293,7 @@ TEST(TimeSynchronizer, immediate4)
   TimeSynchronizer<Msg, Msg, Msg, Msg> sync(1);
   Helper h;
   sync.registerCallback(boost::bind(&Helper::cb, &h));
-  MsgPtr m(new Msg);
+  MsgPtr m(boost::make_shared<Msg>());
   m->header.stamp = ros::Time::now();
 
   sync.add0(m);
@@ -311,7 +311,7 @@ TEST(TimeSynchronizer, immediate5)
   TimeSynchronizer<Msg, Msg, Msg, Msg, Msg> sync(1);
   Helper h;
   sync.registerCallback(boost::bind(&Helper::cb, &h));
-  MsgPtr m(new Msg);
+  MsgPtr m(boost::make_shared<Msg>());
   m->header.stamp = ros::Time::now();
 
   sync.add0(m);
@@ -331,7 +331,7 @@ TEST(TimeSynchronizer, immediate6)
   TimeSynchronizer<Msg, Msg, Msg, Msg, Msg, Msg> sync(1);
   Helper h;
   sync.registerCallback(boost::bind(&Helper::cb, &h));
-  MsgPtr m(new Msg);
+  MsgPtr m(boost::make_shared<Msg>());
   m->header.stamp = ros::Time::now();
 
   sync.add0(m);
@@ -353,7 +353,7 @@ TEST(TimeSynchronizer, immediate7)
   TimeSynchronizer<Msg, Msg, Msg, Msg, Msg, Msg, Msg> sync(1);
   Helper h;
   sync.registerCallback(boost::bind(&Helper::cb, &h));
-  MsgPtr m(new Msg);
+  MsgPtr m(boost::make_shared<Msg>());
   m->header.stamp = ros::Time::now();
 
   sync.add0(m);
@@ -377,7 +377,7 @@ TEST(TimeSynchronizer, immediate8)
   TimeSynchronizer<Msg, Msg, Msg, Msg, Msg, Msg, Msg, Msg> sync(1);
   Helper h;
   sync.registerCallback(boost::bind(&Helper::cb, &h));
-  MsgPtr m(new Msg);
+  MsgPtr m(boost::make_shared<Msg>());
   m->header.stamp = ros::Time::now();
 
   sync.add0(m);
@@ -403,7 +403,7 @@ TEST(TimeSynchronizer, immediate9)
   TimeSynchronizer<Msg, Msg, Msg, Msg, Msg, Msg, Msg, Msg, Msg> sync(1);
   Helper h;
   sync.registerCallback(boost::bind(&Helper::cb, &h));
-  MsgPtr m(new Msg);
+  MsgPtr m(boost::make_shared<Msg>());
   m->header.stamp = ros::Time::now();
 
   sync.add0(m);
@@ -435,13 +435,13 @@ TEST(TimeSynchronizer, multipleTimes)
   TimeSynchronizer<Msg, Msg, Msg> sync(2);
   Helper h;
   sync.registerCallback(boost::bind(&Helper::cb, &h));
-  MsgPtr m(new Msg);
+  MsgPtr m(boost::make_shared<Msg>());
   m->header.stamp = ros::Time();
 
   sync.add0(m);
   ASSERT_EQ(h.count_, 0);
 
-  m.reset(new Msg);
+  m = boost::make_shared<Msg>();
   m->header.stamp = ros::Time(0.1);
   sync.add1(m);
   ASSERT_EQ(h.count_, 0);
@@ -456,7 +456,7 @@ TEST(TimeSynchronizer, queueSize)
   TimeSynchronizer<Msg, Msg, Msg> sync(1);
   Helper h;
   sync.registerCallback(boost::bind(&Helper::cb, &h));
-  MsgPtr m(new Msg);
+  MsgPtr m(boost::make_shared<Msg>());
   m->header.stamp = ros::Time();
 
   sync.add0(m);
@@ -464,12 +464,12 @@ TEST(TimeSynchronizer, queueSize)
   sync.add1(m);
   ASSERT_EQ(h.count_, 0);
 
-  m.reset(new Msg);
+  m = boost::make_shared<Msg>();
   m->header.stamp = ros::Time(0.1);
   sync.add1(m);
   ASSERT_EQ(h.count_, 0);
 
-  m.reset(new Msg);
+  m = boost::make_shared<Msg>();
   m->header.stamp = ros::Time(0);
   sync.add1(m);
   ASSERT_EQ(h.count_, 0);
@@ -483,7 +483,7 @@ TEST(TimeSynchronizer, dropCallback)
   Helper h;
   sync.registerCallback(boost::bind(&Helper::cb, &h));
   sync.registerDropCallback(boost::bind(&Helper::dropcb, &h));
-  MsgPtr m(new Msg);
+  MsgPtr m(boost::make_shared<Msg>());
   m->header.stamp = ros::Time();
 
   sync.add0(m);
@@ -511,7 +511,7 @@ TEST(TimeSynchronizer, eventInEventOut)
   TimeSynchronizer<Msg, Msg> sync(2);
   EventHelper h;
   sync.registerCallback(&EventHelper::callback, &h);
-  ros::MessageEvent<Msg const> evt(MsgPtr(new Msg), ros::Time(4));
+  ros::MessageEvent<Msg const> evt(boost::make_shared<Msg>(), ros::Time(4));
 
   sync.add<0>(evt);
   sync.add<1>(evt);
@@ -528,7 +528,7 @@ TEST(TimeSynchronizer, connectConstructor)
   TimeSynchronizer<Msg, Msg> sync(pt1, pt2, 1);
   Helper h;
   sync.registerCallback(boost::bind(&Helper::cb, &h));
-  MsgPtr m(new Msg);
+  MsgPtr m(boost::make_shared<Msg>());
   m->header.stamp = ros::Time::now();
 
   pt1.add(m);
diff --git a/utilities/roslz4/CHANGELOG.rst b/utilities/roslz4/CHANGELOG.rst
index b62783d..b14f2f6 100644
--- a/utilities/roslz4/CHANGELOG.rst
+++ b/utilities/roslz4/CHANGELOG.rst
@@ -2,6 +2,16 @@
 Changelog for package roslz4
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.12.0 (2016-03-18)
+-------------------
+
+1.11.18 (2016-03-17)
+--------------------
+* fix compiler warnings
+
+1.11.17 (2016-03-11)
+--------------------
+
 1.11.16 (2015-11-09)
 --------------------
 
diff --git a/utilities/roslz4/CMakeLists.txt b/utilities/roslz4/CMakeLists.txt
index 6e539bf..85dbe0a 100644
--- a/utilities/roslz4/CMakeLists.txt
+++ b/utilities/roslz4/CMakeLists.txt
@@ -2,6 +2,10 @@ cmake_minimum_required(VERSION 2.8.3)
 
 project(roslz4)
 
+if(NOT WIN32)
+  set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -Wextra")
+endif()
+
 find_package(catkin REQUIRED)
 
 find_path(lz4_INCLUDE_DIRS NAMES lz4.h)
diff --git a/utilities/roslz4/package.xml b/utilities/roslz4/package.xml
index 42abf0b..fb59d06 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.16</version>
+  <version>1.12.0</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/test/roslz4_test.cpp b/utilities/roslz4/test/roslz4_test.cpp
index e3cc3c5..a0bfe83 100644
--- a/utilities/roslz4/test/roslz4_test.cpp
+++ b/utilities/roslz4/test/roslz4_test.cpp
@@ -39,13 +39,13 @@
 class CompressATest :public testing::Test {
 protected:
   void SetUp() {
-    for (int i = 0; i < sizeof(input); ++i) {
+    for (size_t i = 0; i < sizeof(input); ++i) {
       input[i] = 'a';
     }
-    for (int i = 0; i < sizeof(output); ++i) {
+    for (size_t i = 0; i < sizeof(output); ++i) {
       output[i] = 0;
     }
-    for (int i = 0; i < sizeof(other); ++i) {
+    for (size_t i = 0; i < sizeof(other); ++i) {
       other[i] = 0;
     }
   }
@@ -90,7 +90,7 @@ TEST_F(CompressATest, Stream) {
 
   roslz4_decompressEnd(&stream);
 
-  for (int i = 0; i < sizeof(other); ++i) {
+  for (size_t i = 0; i < sizeof(other); ++i) {
     ASSERT_EQ(input[i], other[i]) <<  "Original and uncompressed data differ at index " << i;
   }
 }
@@ -108,7 +108,7 @@ TEST_F(CompressATest, Oneshot) {
   ASSERT_EQ(ROSLZ4_OK, ret);
   ASSERT_EQ(sizeof(input), decomp_size);
 
-  for (int i = 0; i < sizeof(other); ++i) {
+  for (size_t i = 0; i < sizeof(other); ++i) {
     ASSERT_EQ(input[i], other[i]) << "Original and uncompressed data differ at index " << i;
   }
 }
diff --git a/utilities/roswtf/CHANGELOG.rst b/utilities/roswtf/CHANGELOG.rst
index 9f80ad8..6d490dd 100644
--- a/utilities/roswtf/CHANGELOG.rst
+++ b/utilities/roswtf/CHANGELOG.rst
@@ -2,6 +2,15 @@
 Changelog for package roswtf
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.12.0 (2016-03-18)
+-------------------
+
+1.11.18 (2016-03-17)
+--------------------
+
+1.11.17 (2016-03-11)
+--------------------
+
 1.11.16 (2015-11-09)
 --------------------
 
diff --git a/utilities/roswtf/CMakeLists.txt b/utilities/roswtf/CMakeLists.txt
index 97a34ff..ff7ffa9 100644
--- a/utilities/roswtf/CMakeLists.txt
+++ b/utilities/roswtf/CMakeLists.txt
@@ -6,6 +6,6 @@ catkin_python_setup()
 
 if(CATKIN_ENABLE_TESTING)
   find_package(rostest)
-  add_rostest(test/roswtf.test)
-  catkin_add_nosetests(test)
+  # add_rostest(test/roswtf.test)
+  # catkin_add_nosetests(test)
 endif()
diff --git a/utilities/roswtf/package.xml b/utilities/roswtf/package.xml
index 5539b27..7e3782e 100644
--- a/utilities/roswtf/package.xml
+++ b/utilities/roswtf/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>roswtf</name>
-  <version>1.11.16</version>
+  <version>1.12.0</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/py_pip_deb_checks.py b/utilities/roswtf/src/roswtf/py_pip_deb_checks.py
index 7c77333..618fc53 100644
--- a/utilities/roswtf/src/roswtf/py_pip_deb_checks.py
+++ b/utilities/roswtf/src/roswtf/py_pip_deb_checks.py
@@ -52,9 +52,12 @@ if sys.version_info[0] == 3:
 py_to_deb_core_packages = {
     'catkin_pkg': '%s-catkin-pkg' % python_prefix,
     'rospkg': '%s-rospkg' % python_prefix,
-    'rosinstall': '%s-rosinstall' % python_prefix,
     'rosdep2': '%s-rosdep' % python_prefix,
 }
+# optional ROS python packages and their corresponding .deb packages
+py_to_deb_optional_packages = {
+    'rosinstall': '%s-rosinstall' % python_prefix,
+}
 
 #A dictionary of release ROS python packages and their corresponding .deb packages
 py_to_deb_release_packages = {
@@ -137,7 +140,8 @@ def pip_install_check_on_ubuntu(ctx):
     """Make sure on Ubuntu, Python packages are install with apt and not pip"""
     if (is_host_os_ubuntu()):
         warn_str = ''
-        pt_to_deb_package_names = list(py_to_deb_core_packages.keys()) + list(py_to_deb_release_packages.keys())
+        pt_to_deb_package_names = list(py_to_deb_core_packages.keys()) + \
+            list(py_to_deb_optional_packages.keys()) + list(py_to_deb_release_packages.keys())
         for py_pkg in pt_to_deb_package_names:
             if is_python_package_installed_via_pip_on_ubuntu(py_pkg):
                 warn_str = warn_str + py_pkg + ' -- '
diff --git a/utilities/roswtf/test/test_roswtf_command_line_online.py b/utilities/roswtf/test/check_roswtf_command_line_online.py
similarity index 100%
rename from utilities/roswtf/test/test_roswtf_command_line_online.py
rename to utilities/roswtf/test/check_roswtf_command_line_online.py
diff --git a/utilities/roswtf/test/roswtf.test b/utilities/roswtf/test/roswtf.test
index 877878d..b22d266 100644
--- a/utilities/roswtf/test/roswtf.test
+++ b/utilities/roswtf/test/roswtf.test
@@ -1,3 +1,3 @@
 <launch>
-  <test test-name="roswtf_command_line_online" pkg="roswtf" type="test_roswtf_command_line_online.py" />
+  <test test-name="roswtf_command_line_online" pkg="roswtf" type="check_roswtf_command_line_online.py" />
 </launch>
diff --git a/utilities/roswtf/test/setup.cfg b/utilities/roswtf/test/setup.cfg
deleted file mode 100644
index d4c2614..0000000
--- a/utilities/roswtf/test/setup.cfg
+++ /dev/null
@@ -1,3 +0,0 @@
-[nosetests]
-with-xunit=1
-tests=test_roswtf_command_line_offline.py
diff --git a/utilities/xmlrpcpp/CHANGELOG.rst b/utilities/xmlrpcpp/CHANGELOG.rst
index cebb5bf..3474466 100644
--- a/utilities/xmlrpcpp/CHANGELOG.rst
+++ b/utilities/xmlrpcpp/CHANGELOG.rst
@@ -2,6 +2,15 @@
 Changelog for package xmlrpcpp
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.12.0 (2016-03-18)
+-------------------
+
+1.11.18 (2016-03-17)
+--------------------
+
+1.11.17 (2016-03-11)
+--------------------
+
 1.11.16 (2015-11-09)
 --------------------
 
diff --git a/utilities/xmlrpcpp/CMakeLists.txt b/utilities/xmlrpcpp/CMakeLists.txt
index 89061fd..a4f6bec 100644
--- a/utilities/xmlrpcpp/CMakeLists.txt
+++ b/utilities/xmlrpcpp/CMakeLists.txt
@@ -1,5 +1,10 @@
 cmake_minimum_required(VERSION 2.8.3)
 project(xmlrpcpp)
+
+if(NOT WIN32)
+  set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -Wextra")
+endif()
+
 find_package(catkin REQUIRED COMPONENTS cpp_common)
 catkin_package(
   INCLUDE_DIRS include
diff --git a/utilities/xmlrpcpp/package.xml b/utilities/xmlrpcpp/package.xml
index 1336d78..a9703b7 100644
--- a/utilities/xmlrpcpp/package.xml
+++ b/utilities/xmlrpcpp/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>xmlrpcpp</name>
-  <version>1.11.16</version>
+  <version>1.12.0</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
diff --git a/utilities/xmlrpcpp/src/XmlRpcSocket.cpp b/utilities/xmlrpcpp/src/XmlRpcSocket.cpp
index 916f41d..b3c694b 100644
--- a/utilities/xmlrpcpp/src/XmlRpcSocket.cpp
+++ b/utilities/xmlrpcpp/src/XmlRpcSocket.cpp
@@ -216,9 +216,6 @@ XmlRpcSocket::connect(int fd, std::string& host, int port)
   bool found = false;
   struct addrinfo* it = addr;
 
-  socklen_t len;
-  struct sockaddr *address;
-
   for (; it; it = it->ai_next)
   {
     if (!s_use_ipv6_ && it->ai_family == AF_INET)

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



More information about the debian-science-commits mailing list